Skip to content
This repository has been archived by the owner on Apr 15, 2024. It is now read-only.

Refactor Wombat #4

Merged
merged 4 commits into from
Nov 4, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions .github/dependabot.yml
Original file line number Diff line number Diff line change
Expand Up @@ -7,4 +7,8 @@ version: 2
directory: "/wombat"
schedule:
interval: "daily"
- package-ecosystem: "github-actions"
directory: "/"
schedule:
interval: "daily"

35 changes: 18 additions & 17 deletions wombat/src/main/cpp/drivetrain/Drivetrain.cpp
Original file line number Diff line number Diff line change
@@ -1,38 +1,39 @@
#include "drivetrain/Drivetrain.h"

using namespace wom;
using namespace frc;
using namespace units;

Drivetrain::Drivetrain(DrivetrainConfig *config, XboxController &driver): _config(config), _driver(driver) {}
Drivetrain::~Drivetrain() {}
wom::drivetrain::Drivetrain::Drivetrain(wom::drivetrain::DrivetrainConfig *config, XboxController &driver): _config(config), _driver(driver) {}
wom::drivetrain::Drivetrain::~Drivetrain() {}

DrivetrainConfig *Drivetrain::GetConfig() { return _config; }
DrivetrainState Drivetrain::GetState() { return _state; }
wom::drivetrain::DrivetrainConfig *wom::drivetrain::Drivetrain::GetConfig() { return _config; }
wom::drivetrain::DrivetrainState wom::drivetrain::Drivetrain::GetState() { return _state; }

void Drivetrain::SetState(DrivetrainState state) { _state = state; }
void wom::drivetrain::Drivetrain::SetState(wom::drivetrain::DrivetrainState state) { _state = state; }

void Drivetrain::OnStart() {
void wom::drivetrain::Drivetrain::OnStart() {
std::cout << "Starting Tank" << std::endl;
}

void Drivetrain::OnUpdate(second_t dt) {
switch(_state) {
case DrivetrainState::kIdle:
break;
case DrivetrainState::kTank:
{
double rightSpeed = deadzone(_driver.GetRightY());
double leftSpeed = deadzone(_driver.GetLeftY());
void wom::drivetrain::Drivetrain::TankControl() {
double rightSpeed = wom::utils::deadzone(_driver.GetRightY());
double leftSpeed = wom::utils::deadzone(_driver.GetLeftY());
_config->left1.transmission->SetVoltage(leftSpeed * maxVolts);
_config->left2.transmission->SetVoltage(leftSpeed * maxVolts);
_config->left3.transmission->SetVoltage(leftSpeed * maxVolts);
_config->right1.transmission->SetVoltage(rightSpeed * maxVolts);
_config->right2.transmission->SetVoltage(rightSpeed * maxVolts);
_config->right3.transmission->SetVoltage(rightSpeed * maxVolts);
}

void wom::drivetrain::Drivetrain::OnUpdate(second_t dt) {
switch(_state) {
case wom::drivetrain::DrivetrainState::kIdle:
break;
}
case DrivetrainState::kAuto:
case wom::drivetrain::DrivetrainState::kTank:
{
TankControl();
break;
}
}
}
10 changes: 5 additions & 5 deletions wombat/src/main/cpp/drivetrain/SwerveDrive.cpp
Original file line number Diff line number Diff line change
@@ -1,24 +1,24 @@
#include "drivetrain/SwerveDrive.h"

wom::SwerveModule::SwerveModule(wom::SwerveModuleName name, wom::SwerveModuleConfig config, wom::SwerveModuleState state) :
wom::drivetrain::SwerveModule::SwerveModule(wom::drivetrain::SwerveModuleName name, wom::drivetrain::SwerveModuleConfig config, wom::drivetrain::SwerveModuleState state) :
_name(name),
_config(config),
_state(state)
{}

wom::SwerveModuleName wom::SwerveModule::GetName() {
wom::drivetrain::SwerveModuleName wom::drivetrain::SwerveModule::GetName() {
return _name;
}

wom::SwerveModuleConfig wom::SwerveModule::GetConfig() {
wom::drivetrain::SwerveModuleConfig wom::drivetrain::SwerveModule::GetConfig() {
return _config;
}

wom::SwerveModuleState wom::SwerveModule::GetState() {
wom::drivetrain::SwerveModuleState wom::drivetrain::SwerveModule::GetState() {
return _state;
}

void wom::SwerveModule::SetState(wom::SwerveModuleState state) {
void wom::drivetrain::SwerveModule::SetState(wom::drivetrain::SwerveModuleState state) {
_state = state;
}

10 changes: 10 additions & 0 deletions wombat/src/main/cpp/drivetrain/behaviours/DrivetrainBehaviours.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#include "drivetrain/behaviours/DrivetrainBehaviours.h"

wom::drivetrain::behaviours::TankDrive::TankDrive(wom::drivetrain::Drivetrain *drivebase) : _drivebase(drivebase) {
Controls(drivebase);
}

void wom::drivetrain::behaviours::TankDrive::OnTick(units::second_t dt) {
_drivebase->SetState(wom::drivetrain::DrivetrainState::kTank);
}

41 changes: 20 additions & 21 deletions wombat/src/main/cpp/subsystems/Arm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,9 @@
#include <units/math.h>

using namespace frc;
using namespace wom;

//creates network table instatnce on shuffleboard
void ArmConfig::WriteNT(std::shared_ptr<nt::NetworkTable> table) {
void wom::subsystems::ArmConfig::WriteNT(std::shared_ptr<nt::NetworkTable> table) {
table->GetEntry("armMass").SetDouble(armMass.value());
table->GetEntry("loadMass").SetDouble(loadMass.value());
table->GetEntry("armLength").SetDouble(armLength.value());
Expand All @@ -17,7 +16,7 @@ void ArmConfig::WriteNT(std::shared_ptr<nt::NetworkTable> table) {
}

//arm config is used
Arm::Arm(ArmConfig config)
wom::subsystems::Arm::Arm(wom::subsystems::ArmConfig config)
: _config(config),
_pid(config.path + "/pid", config.pidConfig),
_velocityPID(config.path + "/velocityPID", config.velocityConfig),
Expand All @@ -26,16 +25,16 @@ Arm::Arm(ArmConfig config)
}

//the loop that allows the information to be used
void Arm::OnUpdate(units::second_t dt) {
void wom::subsystems::Arm::OnUpdate(units::second_t dt) {
//sets the voltage and gets the current angle
units::volt_t voltage = 0_V;
auto angle = GetAngle();

//sets usable infromation for each state
switch (_state) {
case ArmState::kIdle:
case wom::subsystems::ArmState::kIdle:
break;
case ArmState::kVelocity:
case wom::subsystems::ArmState::kVelocity:
{
units::newton_meter_t torque = 9.81_m / 1_s / 1_s * _config.armLength * units::math::cos(angle + _config.angleOffset) * (0.5 * _config.armMass + _config.loadMass);
// units::volt_t feedforward = _config.leftGearbox.motor.Voltage(torque, 0_rad/1_s);
Expand All @@ -47,15 +46,15 @@ void Arm::OnUpdate(units::second_t dt) {
// voltage = 0_V;
}
break;
case ArmState::kAngle:
case wom::subsystems::ArmState::kAngle:
{
units::newton_meter_t torque = 9.81_m / 1_s / 1_s * _config.armLength * units::math::cos(angle + _config.angleOffset) * (0.5 * _config.armMass + _config.loadMass);
units::volt_t feedforward = _config.leftGearbox.motor.Voltage(torque, 0_rad/ 1_s);
// std::cout << "feedforward" << feedforward.value() << std::endl;
voltage = _pid.Calculate(angle, dt, feedforward);
}
break;
case ArmState::kRaw:
case wom::subsystems::ArmState::kRaw:
voltage = _voltage;
break;
}
Expand Down Expand Up @@ -89,48 +88,48 @@ void Arm::OnUpdate(units::second_t dt) {
_config.WriteNT(_table->GetSubTable("config"));
}

void Arm::SetArmSpeedLimit(double limit) {
void wom::subsystems::Arm::SetArmSpeedLimit(double limit) {
armLimit = limit;
}

//defines information needed for the functions and connects the states to their respective function

void Arm::SetIdle() {
void wom::subsystems::Arm::SetIdle() {
_state = ArmState::kIdle;
}

void Arm::SetRaw(units::volt_t voltage) {
_state = ArmState::kRaw;
void wom::subsystems::Arm::SetRaw(units::volt_t voltage) {
_state = wom::subsystems::ArmState::kRaw;
_voltage = voltage;
}

void Arm::SetAngle(units::radian_t angle) {
_state = ArmState::kAngle;
void wom::subsystems::Arm::SetAngle(units::radian_t angle) {
_state = wom::subsystems::ArmState::kAngle;
_pid.SetSetpoint(angle);
}

void Arm::SetVelocity(units::radians_per_second_t velocity) {
_state = ArmState::kVelocity;
void wom::subsystems::Arm::SetVelocity(units::radians_per_second_t velocity) {
_state = wom::subsystems::ArmState::kVelocity;
_velocityPID.SetSetpoint(velocity);
}

ArmConfig &Arm::GetConfig() {
wom::subsystems::ArmConfig &wom::subsystems::Arm::GetConfig() {
return _config;
}

units::radian_t Arm::GetAngle() const {
units::radian_t wom::subsystems::Arm::GetAngle() const {
return _config.armEncoder.GetPosition() / 100 * 360 * 1_deg;
}

units::radians_per_second_t Arm::MaxSpeed() const {
units::radians_per_second_t wom::subsystems::Arm::MaxSpeed() const {
return _config.leftGearbox.motor.Speed(0_Nm, 12_V);
}

units::radians_per_second_t Arm::GetArmVelocity() const {
units::radians_per_second_t wom::subsystems::Arm::GetArmVelocity() const {
return _config.armEncoder.GetVelocity() / 100 * 360 * 1_deg / 60_s;
}

bool Arm::IsStable() const {
bool wom::subsystems::Arm::IsStable() const {
return _pid.IsStable(5_deg);
}

Expand Down
48 changes: 24 additions & 24 deletions wombat/src/main/cpp/subsystems/Elevator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,33 +6,33 @@

using namespace wom;

void ElevatorConfig::WriteNT(std::shared_ptr<nt::NetworkTable> table) {
void wom::subsystems::ElevatorConfig::WriteNT(std::shared_ptr<nt::NetworkTable> table) {
table->GetEntry("radius").SetDouble(radius.value());
table->GetEntry("mass").SetDouble(mass.value());
table->GetEntry("maxHeight").SetDouble(maxHeight.value());
}

Elevator::Elevator(ElevatorConfig config)
: _config(config), _state(ElevatorState::kIdle),
wom::subsystems::Elevator::Elevator(wom::subsystems::ElevatorConfig config)
: _config(config), _state(wom::subsystems::ElevatorState::kIdle),
_pid{config.path + "/pid", config.pid},
_velocityPID{config.path + "/velocityPID", config.velocityPID},
_table(nt::NetworkTableInstance::GetDefault().GetTable(config.path)) {
// _config.leftGearbox.encoder->SetEncoderPosition(_config.initialHeight / _config.radius * 1_rad);
}

void Elevator::OnUpdate(units::second_t dt) {
void wom::subsystems::Elevator::OnUpdate(units::second_t dt) {
units::volt_t voltage{0};

units::meter_t height = GetElevatorEncoderPos() * 1_m;

switch(_state) {
case ElevatorState::kIdle:
case wom::subsystems::ElevatorState::kIdle:
voltage = 0_V;
break;
case ElevatorState::kManual:
case wom::subsystems::ElevatorState::kManual:
voltage = _setpointManual;
break;
case ElevatorState::kVelocity:
case wom::subsystems::ElevatorState::kVelocity:
{
units::volt_t feedforward = _config.rightGearbox.motor.Voltage((_config.mass * 9.81_mps_sq) * _config.radius, _velocityPID.GetSetpoint() / (14.0/60.0 * 2.0 * 3.1415 * 0.02225 * 1_m) * 1_rad);
// units::volt_t feedforward = _config.rightGearbox.motor.Voltage(0_Nm, _velocityPID.GetSetpoint() / (14.0/60.0 * 2.0 * 3.1415 * 0.02225 * 1_m) * 1_rad);
Expand All @@ -45,7 +45,7 @@ void Elevator::OnUpdate(units::second_t dt) {
// voltage = 0_V;
}
break;
case ElevatorState::kPID:
case wom::subsystems::ElevatorState::kPID:
{
units::volt_t feedforward = _config.rightGearbox.motor.Voltage((_config.mass * 9.81_mps_sq) * _config.radius, 0_rad_per_s);
// std::cout << "feed forward" << feedforward.value() << std::endl;
Expand Down Expand Up @@ -83,55 +83,55 @@ void Elevator::OnUpdate(units::second_t dt) {
_config.rightGearbox.transmission->SetVoltage(voltage);
}

void Elevator::SetManual(units::volt_t voltage) {
_state = ElevatorState::kManual;
void wom::subsystems::Elevator::SetManual(units::volt_t voltage) {
_state = wom::subsystems::ElevatorState::kManual;
_setpointManual = voltage;
}

void Elevator::SetPID(units::meter_t height) {
_state = ElevatorState::kPID;
void wom::subsystems::Elevator::SetPID(units::meter_t height) {
_state = wom::subsystems::ElevatorState::kPID;
_pid.SetSetpoint(height);
}

void Elevator::SetElevatorSpeedLimit(double limit) {
void wom::subsystems::Elevator::SetElevatorSpeedLimit(double limit) {
speedLimit = limit;
}

void Elevator::SetVelocity(units::meters_per_second_t velocity) {
void wom::subsystems::Elevator::SetVelocity(units::meters_per_second_t velocity) {
_velocityPID.SetSetpoint(velocity);
_state = ElevatorState::kVelocity;
_state = wom::subsystems::ElevatorState::kVelocity;
}

void Elevator::SetIdle() {
_state = ElevatorState::kIdle;
void wom::subsystems::Elevator::SetIdle() {
_state = wom::subsystems::ElevatorState::kIdle;
}

ElevatorConfig &Elevator::GetConfig() {
wom::subsystems::ElevatorConfig &wom::subsystems::Elevator::GetConfig() {
return _config;
}

bool Elevator::IsStable() const {
bool wom::subsystems::Elevator::IsStable() const {
return _pid.IsStable();
}

ElevatorState Elevator::GetState() const {
wom::subsystems::ElevatorState wom::subsystems::Elevator::GetState() const {
return _state;
}

double Elevator::GetElevatorEncoderPos() {
double wom::subsystems::Elevator::GetElevatorEncoderPos() {
return _config.elevatorEncoder.GetPosition() * 14/60 * 2 * 3.1415 * 0.02225;
}

units::meter_t Elevator::GetHeight() const {
units::meter_t wom::subsystems::Elevator::GetHeight() const {
// std::cout << "elevator position"<< _config.rightGearbox.encoder->GetEncoderTicks() << std::endl;
// return _config.rightGearbox.encoder->GetEncoderDistance() * 1_m;
return _config.elevatorEncoder.GetPosition() * 14/60 * 2 * 3.1415 * 0.02225 * 1_m;
}

units::meters_per_second_t Elevator::GetElevatorVelocity() const {
units::meters_per_second_t wom::subsystems::Elevator::GetElevatorVelocity() const {
return _config.elevatorEncoder.GetVelocity() / 60_s * 14/60 * 2 * 3.1415 * 0.02225 * 1_m;
}

units::meters_per_second_t Elevator::MaxSpeed() const {
units::meters_per_second_t wom::subsystems::Elevator::MaxSpeed() const {
return _config.leftGearbox.motor.Speed((_config.mass * 9.81_mps_sq) * _config.radius, 12_V) / 1_rad * _config.radius;
}
Loading