Skip to content

Commit

Permalink
Reapply "[wombat] migrate off VoltageController (CurtinFRC#70)" (Curt…
Browse files Browse the repository at this point in the history
…inFRC#80)

This reverts commit d3c4c72.
  • Loading branch information
spacey-sooty committed Jan 16, 2024
1 parent c7a8728 commit fe299c0
Show file tree
Hide file tree
Showing 12 changed files with 33 additions and 130 deletions.
16 changes: 8 additions & 8 deletions src/main/include/RobotMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,43 +65,43 @@ struct RobotMap {
// front left module
frc::Translation2d(10.761_in, 9.455_in),
wom::Gearbox{
new wom::VoltageController(driveMotors[0]),
driveMotors[0],
new wom::TalonFXEncoder(driveMotors[0], 0.0445_m, 6.75),
frc::DCMotor::Falcon500(1).WithReduction(6.75)},
wom::Gearbox{new wom::VoltageController(turnMotors[0]),
wom::Gearbox{turnMotors[0],
new wom::CanEncoder(19, 0.0445_m, 4096, 12.8),
frc::DCMotor::Falcon500(1).WithReduction(12.8)},
&frontLeftCancoder, 4_in / 2},
wom::SwerveModuleConfig{
// front right module
frc::Translation2d(10.761_in, -9.455_in),
wom::Gearbox{
new wom::VoltageController(driveMotors[1]),
driveMotors[1],
new wom::TalonFXEncoder(driveMotors[1], 0.0445_m, 6.75),
frc::DCMotor::Falcon500(1).WithReduction(6.75)},
wom::Gearbox{new wom::VoltageController(turnMotors[1]),
wom::Gearbox{turnMotors[1],
new wom::CanEncoder(17, 0.0445_m, 4096, 12.8),
frc::DCMotor::Falcon500(1).WithReduction(12.8)},
&frontRightCancoder, 4_in / 2},
wom::SwerveModuleConfig{
// back left module
frc::Translation2d(-10.761_in, 9.455_in),
wom::Gearbox{
new wom::VoltageController(driveMotors[2]),
driveMotors[2],
new wom::TalonFXEncoder(driveMotors[2], 0.0445_m, 6.75),
frc::DCMotor::Falcon500(1).WithReduction(6.75)},
wom::Gearbox{new wom::VoltageController(turnMotors[2]),
wom::Gearbox{turnMotors[2],
new wom::CanEncoder(16, 0.0445_m, 4096, 12.8),
frc::DCMotor::Falcon500(1).WithReduction(12.8)},
&backRightCancoder, 4_in / 2},
wom::SwerveModuleConfig{
// back right module
frc::Translation2d(-10.761_in, -9.455_in),
wom::Gearbox{
new wom::VoltageController(driveMotors[3]),
driveMotors[3],
new wom::TalonFXEncoder(driveMotors[3], 0.0445_m, 6.75),
frc::DCMotor::Falcon500(1).WithReduction(6.75)},
wom::Gearbox{new wom::VoltageController(turnMotors[3]),
wom::Gearbox{turnMotors[3],
new wom::CanEncoder(18, 0.0445_m, 4096, 12.8),
frc::DCMotor::Falcon500(1).WithReduction(12.8)},
&backLeftCancoder, 4_in / 2},
Expand Down
12 changes: 6 additions & 6 deletions wombat/src/main/cpp/drivetrain/Drivetrain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,12 @@ void wom::drivetrain::Drivetrain::OnUpdate(second_t dt) {
case DrivetrainState::kTank: {
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);
_config->left1.motorController->SetVoltage(leftSpeed * maxVolts);
_config->left2.motorController->SetVoltage(leftSpeed * maxVolts);
_config->left3.motorController->SetVoltage(leftSpeed * maxVolts);
_config->right1.motorController->SetVoltage(rightSpeed * maxVolts);
_config->right2.motorController->SetVoltage(rightSpeed * maxVolts);
_config->right3.motorController->SetVoltage(rightSpeed * maxVolts);
break;
}
case DrivetrainState::kAuto:
Expand Down
4 changes: 2 additions & 2 deletions wombat/src/main/cpp/drivetrain/SwerveDrive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,8 +81,8 @@ void SwerveModule::OnUpdate(units::second_t dt) {
// turnVoltage = units::math::min(units::math::max(turnVoltage, -7_V), 7_V);
// std::cout << "turn-voltage-max: " << turnVoltageMax.value() << std::endl;

_config.driveMotor.transmission->SetVoltage(driveVoltage);
_config.turnMotor.transmission->SetVoltage(turnVoltage);
_config.driveMotor.motorController->SetVoltage(driveVoltage);
_config.turnMotor.motorController->SetVoltage(turnVoltage);

_table->GetEntry("speed").SetDouble(GetSpeed().value());
_table->GetEntry("angle").SetDouble(
Expand Down
4 changes: 2 additions & 2 deletions wombat/src/main/cpp/subsystems/Arm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,8 @@ void wom::subsystems::Arm::OnUpdate(units::second_t dt) {

// std::cout << "voltage: " << voltage.value() << std::endl;

_config.leftGearbox.transmission->SetVoltage(voltage);
_config.rightGearbox.transmission->SetVoltage(voltage);
_config.leftGearbox.motorController->SetVoltage(voltage);
_config.rightGearbox.motorController->SetVoltage(voltage);

// creates network table instances for the angle and config of the arm
_table->GetEntry("angle").SetDouble(angle.convert<units::degree>().value());
Expand Down
4 changes: 2 additions & 2 deletions wombat/src/main/cpp/subsystems/Elevator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,8 +87,8 @@ void wom::subsystems::Elevator::OnUpdate(units::second_t dt) {

// Set voltage to motors...
voltage *= speedLimit;
_config.leftGearbox.transmission->SetVoltage(voltage);
_config.rightGearbox.transmission->SetVoltage(voltage);
_config.leftGearbox.motorController->SetVoltage(voltage);
_config.rightGearbox.motorController->SetVoltage(voltage);
}

void wom::subsystems::Elevator::SetManual(units::volt_t voltage) {
Expand Down
2 changes: 1 addition & 1 deletion wombat/src/main/cpp/subsystems/Shooter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ void wom::subsystems::Shooter::OnUpdate(units::second_t dt) {
voltage =
1_V * std::min(voltage.value(), max_voltage_for_current_limit.value());

_params.gearbox.transmission->SetVoltage(voltage);
_params.gearbox.motorController->SetVoltage(voltage);

_table->GetEntry("output_volts").SetDouble(voltage.value());
_table->GetEntry("speed_rpm").SetDouble(currentSpeed.value());
Expand Down
6 changes: 6 additions & 0 deletions wombat/src/main/cpp/utils/Util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@

#include <frc/RobotController.h>

#include "units/voltage.h"

units::second_t wom::utils::now() {
uint64_t now = frc::RobotController::GetFPGATime();
return static_cast<double>(now) / 1000000 * 1_s;
Expand Down Expand Up @@ -44,6 +46,10 @@ units::volt_t wom::utils::LimitVoltage(units::volt_t voltage) {
return voltage;
}

units::volt_t wom::utils::GetVoltage(frc::MotorController* controller) {
return controller->Get() * frc::RobotController::GetBatteryVoltage();
}

void wom::utils::WriteTrajectory(std::shared_ptr<nt::NetworkTable> table,
frc::Trajectory trajectory) {
table->GetEntry("length").SetDouble(trajectory.TotalTime().value());
Expand Down
36 changes: 0 additions & 36 deletions wombat/src/main/cpp/utils/VoltageController.cpp

This file was deleted.

1 change: 0 additions & 1 deletion wombat/src/main/include/Wombat.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include "utils/PID.h"
#include "utils/RobotStartup.h"
#include "utils/Util.h"
#include "utils/VoltageController.h"

namespace wom {
using namespace wom;
Expand Down
10 changes: 5 additions & 5 deletions wombat/src/main/include/utils/Gearbox.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@

#pragma once

#include <frc/motorcontrol/MotorController.h>
#include <frc/system/plant/DCMotor.h>

#include "VoltageController.h"
#include "utils/Encoder.h"

namespace wom {
Expand All @@ -19,19 +19,19 @@ namespace utils {
*/
struct Gearbox {
/**
* The VoltageController (Motor Controller). May not be null.
* The MotorController. May not be null.
*/
VoltageController* transmission;
frc::MotorController* motorController;

/**
* The Encoder. May be null, depending on the consumer of this structure.
*/
Encoder* encoder = nullptr;

/**
* The motor being used. By default, this is a dual CIM.
* The motor being used. By default, this is a single Neo.
*/
frc::DCMotor motor = frc::DCMotor::CIM(2);
frc::DCMotor motor = frc::DCMotor::NEO(1);
};
} // namespace utils
} // namespace wom
2 changes: 1 addition & 1 deletion wombat/src/main/include/utils/Util.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@

#pragma once

#include <frc/RobotController.h>
#include <frc/geometry/Pose3d.h>
#include <frc/motorcontrol/MotorController.h>
#include <frc/trajectory/Trajectory.h>
Expand Down Expand Up @@ -106,5 +105,6 @@ double deadzone(double val, double deadzone = 0.05);
double spow2(double val);

units::volt_t LimitVoltage(units::volt_t voltage);
units::volt_t GetVoltage(frc::MotorController* controller);
} // namespace utils
} // namespace wom
66 changes: 0 additions & 66 deletions wombat/src/main/include/utils/VoltageController.h

This file was deleted.

0 comments on commit fe299c0

Please sign in to comment.