Skip to content

Commit

Permalink
Update code to use new Phoenix/WPILib beta features
Browse files Browse the repository at this point in the history
  • Loading branch information
CoryNessCTR committed Oct 19, 2023
1 parent ebd9cda commit 5fa6ba7
Show file tree
Hide file tree
Showing 18 changed files with 52 additions and 50 deletions.
5 changes: 4 additions & 1 deletion cpp/CommandBasedDrive/.vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -14,5 +14,8 @@
"**/.factorypath": true,
"**/*~": true
},
"C_Cpp.default.configurationProvider": "vscode-wpilib"
"C_Cpp.default.configurationProvider": "vscode-wpilib",
"files.associations": {
"concepts": "cpp"
}
}
8 changes: 7 additions & 1 deletion cpp/CommandBasedDrive/src/main/cpp/RobotContainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,13 @@
RobotContainer::RobotContainer()
{
// Initialize all of your commands and subsystems here
m_driveSubsystem.SetDefaultCommand(m_teleopDrive);
frc2::RunCommand teleopDrive {[this]()
{
/* invert the joystick Y because forward Y is negative */
m_driveSubsystem.ArcadeDrive(-m_joystick.GetLeftY(), m_joystick.GetRightX());
},
{&m_driveSubsystem}};
m_driveSubsystem.SetDefaultCommand(std::move(teleopDrive));

// Configure the button bindings
ConfigureButtonBindings();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ void DriveSubsystem::InitializeLeftDriveTalonFX(ctre::phoenix6::configs::TalonFX
cfg.Apply(toApply);

/* And initialize position to 0 */
cfg.SetRotorPosition(0_tr);
cfg.SetPosition(0_tr);
}
void DriveSubsystem::InitializeRightDriveTalonFX(ctre::phoenix6::configs::TalonFXConfigurator &cfg)
{
Expand All @@ -84,7 +84,7 @@ void DriveSubsystem::InitializeRightDriveTalonFX(ctre::phoenix6::configs::TalonF
cfg.Apply(toApply);

/* And initialize position to 0 */
cfg.SetRotorPosition(0_tr);
cfg.SetPosition(0_tr);
}
void DriveSubsystem::InitializePigeon2(ctre::phoenix6::configs::Pigeon2Configurator &cfg)
{
Expand Down
7 changes: 0 additions & 7 deletions cpp/CommandBasedDrive/src/main/include/RobotContainer.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,6 @@ class RobotContainer
frc::XboxController m_joystick{0};

DriveSubsystem m_driveSubsystem{};

frc2::RunCommand m_teleopDrive{[this]()
{
/* invert the joystick Y because forward Y is negative */
m_driveSubsystem.ArcadeDrive(-m_joystick.GetLeftY(), m_joystick.GetRightX());
},
{&m_driveSubsystem}};
DriveStraightCommand m_driveStraightCommand{m_driveSubsystem,
[this]()
{ return -m_joystick.GetLeftY(); }};
Expand Down
10 changes: 5 additions & 5 deletions cpp/FusedCANcoder/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,9 @@ void Robot::RobotPeriodic() {
// If any faults happen, print them out. Sticky faults will always be present if live-fault occurs
f_fusedSensorOutOfSync.Refresh();
sf_fusedSensorOutOfSync.Refresh();
f_missingRemoteSensor.Refresh();
sf_missingRemoteSensor.Refresh();
bool anyFault = sf_fusedSensorOutOfSync.GetValue() || sf_missingRemoteSensor.GetValue();
f_remoteSensorInvalid.Refresh();
sf_remoteSensorInvalid.Refresh();
bool anyFault = sf_fusedSensorOutOfSync.GetValue() || sf_remoteSensorInvalid.GetValue();
if(anyFault) {
std::cout << "A fault has occurred:" << std::endl;;
/* If we're live, indicate live, otherwise if we're sticky indicate sticky, otherwise do nothing */
Expand All @@ -41,9 +41,9 @@ void Robot::RobotPeriodic() {
std::cout << "Fused sensor out of sync sticky-faulted" << std::endl;
}
/* If we're live, indicate live, otherwise if we're sticky indicate sticky, otherwise do nothing */
if(f_missingRemoteSensor.GetValue()) {
if(f_remoteSensorInvalid.GetValue()) {
std::cout << "Missing remote sensor live-faulted" << std::endl;
} else if (sf_missingRemoteSensor.GetValue()) {
} else if (sf_remoteSensorInvalid.GetValue()) {
std::cout << "Missing remote sensor sticky-faulted" << std::endl;
}
}
Expand Down
4 changes: 2 additions & 2 deletions cpp/FusedCANcoder/src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ class Robot : public frc::TimedRobot {
ctre::phoenix6::hardware::CANcoder m_cc{1, "fred"};
ctre::phoenix6::StatusSignal<bool> f_fusedSensorOutOfSync = m_fx.GetFault_FusedSensorOutOfSync();
ctre::phoenix6::StatusSignal<bool> sf_fusedSensorOutOfSync = m_fx.GetStickyFault_FusedSensorOutOfSync();
ctre::phoenix6::StatusSignal<bool> f_missingRemoteSensor = m_fx.GetFault_MissingRemoteSensor();
ctre::phoenix6::StatusSignal<bool> sf_missingRemoteSensor = m_fx.GetStickyFault_MissingRemoteSensor();
ctre::phoenix6::StatusSignal<bool> f_remoteSensorInvalid = m_fx.GetFault_RemoteSensorDataInvalid();
ctre::phoenix6::StatusSignal<bool> sf_remoteSensorInvalid = m_fx.GetStickyFault_RemoteSensorDataInvalid();

ctre::phoenix6::StatusSignal<units::turn_t> fx_pos = m_fx.GetPosition();
ctre::phoenix6::StatusSignal<units::turns_per_second_t> fx_vel = m_fx.GetVelocity();
Expand Down
2 changes: 1 addition & 1 deletion cpp/PositionClosedLoop/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ void Robot::RobotInit() {
m_fx.GetConfigurator().Apply(configs);

/* Make sure we start at 0 */
m_fx.SetRotorPosition(0_tr);
m_fx.SetPosition(0_tr);
}
void Robot::RobotPeriodic() {}

Expand Down
4 changes: 2 additions & 2 deletions cpp/PositionClosedLoop/src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@

class Robot : public frc::TimedRobot {
ctre::phoenix6::hardware::TalonFX m_fx{0};
ctre::phoenix6::controls::PositionVoltage m_voltagePosition{0_tr, true, 0_V, 0, false};
ctre::phoenix6::controls::PositionTorqueCurrentFOC m_torquePosition{0_tr, 0_A, 1, false};
ctre::phoenix6::controls::PositionVoltage m_voltagePosition{0_tr, 0_tps, true, 0_V, 0, false};
ctre::phoenix6::controls::PositionTorqueCurrentFOC m_torquePosition{0_tr, 0_tps, 0_A, 1, false};
ctre::phoenix6::controls::StaticBrake m_brake{};

frc::XboxController m_joystick{0};
Expand Down
4 changes: 2 additions & 2 deletions cpp/VelocityClosedLoop/src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@

class Robot : public frc::TimedRobot {
ctre::phoenix6::hardware::TalonFX m_fx{0};
ctre::phoenix6::controls::VelocityVoltage m_voltageVelocity{0_tps, true, 0_V, 0, false};
ctre::phoenix6::controls::VelocityTorqueCurrentFOC m_torqueVelocity{0_tps, 0_A, 1, false};
ctre::phoenix6::controls::VelocityVoltage m_voltageVelocity{0_tps, 0_tr_per_s_sq, true, 0_V, 0, false};
ctre::phoenix6::controls::VelocityTorqueCurrentFOC m_torqueVelocity{0_tps, 0_tr_per_s_sq, 0_A, 1, false};
ctre::phoenix6::controls::StaticBrake m_brake{};

frc::XboxController m_joystick{0};
Expand Down
8 changes: 4 additions & 4 deletions cpp/WaitForAll/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,23 +22,23 @@ void Robot::RobotPeriodic() {
ctre::phoenix::StatusCode status = ctre::phoenix6::BaseStatusSignal::WaitForAll(m_waitForAllTimeout, m_lotsOfSignals);
std::cout << "Status of waiting on signals (normal use case): " << status.GetName() << std::endl;
for(auto const &sig : m_lotsOfSignals) {
std::cout << "Signal status: " << sig->GetError().GetName() << std::endl;
std::cout << "Signal status: " << sig->GetStatus().GetName() << std::endl;
}
}
/* If we press the B button, test what happens when we wait on signals from different busses */
if(m_joystick.GetBButtonPressed()) {
ctre::phoenix::StatusCode status = ctre::phoenix6::BaseStatusSignal::WaitForAll(m_waitForAllTimeout, m_signalsAcrossCANbuses);
std::cout << "Status of waiting on signals across different CAN busses: " << status.GetName() << std::endl;
for(auto const& sig : m_signalsAcrossCANbuses) {
std::cout << "Signal status: " << sig->GetError().GetName() << std::endl;
std::cout << "Signal status: " << sig->GetStatus().GetName() << std::endl;
}
}
/* If we press the Y button, test what happens when we wait on no signals */
if(m_joystick.GetYButtonPressed()) {
ctre::phoenix::StatusCode status = ctre::phoenix6::BaseStatusSignal::WaitForAll(m_waitForAllTimeout, m_noSignals);
std::cout << "Status of waiting on no signals: " << status.GetName() << std::endl;
for(auto const& sig : m_noSignals) {
std::cout << "Signal status: " << sig->GetError().GetName() << std::endl;
std::cout << "Signal status: " << sig->GetStatus().GetName() << std::endl;
}
}
/* If we press the X button, test what happens when we wait on signals with the transcient motor controller */
Expand All @@ -49,7 +49,7 @@ void Robot::RobotPeriodic() {
&m_canbus1transcient2});
std::cout << "Status of waiting on transcient signals: " << status.GetName() << std::endl;
for(auto const& sig : m_tanscientSignals) {
std::cout << "Signal status: " << sig->GetError().GetName() << std::endl;
std::cout << "Signal status: " << sig->GetStatus().GetName() << std::endl;
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ public void testLatencyCompensator() {
final double position = 35;
final double velocity = 24;
/* Initialize by making all the positions 0 */
talonfx.setRotorPosition(0);
talonfx.setPosition(0);
cancoder.setPosition(0);

/* Set the simulated state of device positions */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,7 @@ private void initializeLeftDriveTalonFX(TalonFXConfigurator cfg) {
cfg.apply(toApply);

/* And initialize position to 0 */
cfg.setRotorPosition(0);
cfg.setPosition(0);
}

/**
Expand All @@ -273,7 +273,7 @@ private void initializeRightDriveTalonFX(TalonFXConfigurator cfg) {
cfg.apply(toApply);

/* And initialize position to 0 */
cfg.setRotorPosition(0);
cfg.setPosition(0);
}

/**
Expand Down
14 changes: 7 additions & 7 deletions java/FusedCANcoder/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ public class Robot extends TimedRobot {
CANcoder m_cc = new CANcoder(1, "fred");
StatusSignal<Boolean> f_fusedSensorOutOfSync = m_fx.getFault_FusedSensorOutOfSync();
StatusSignal<Boolean> sf_fusedSensorOutOfSync = m_fx.getStickyFault_FusedSensorOutOfSync();
StatusSignal<Boolean> f_missingRemoteSensor = m_fx.getFault_MissingRemoteSensor();
StatusSignal<Boolean> sf_missingRemoteSensor = m_fx.getStickyFault_MissingRemoteSensor();
StatusSignal<Boolean> f_remoteSensorInvalid = m_fx.getFault_RemoteSensorDataInvalid();
StatusSignal<Boolean> sf_remoteSensorInvalid = m_fx.getStickyFault_RemoteSensorDataInvalid();

StatusSignal<Double> fx_pos = m_fx.getPosition();
StatusSignal<Double> fx_vel = m_fx.getVelocity();
Expand Down Expand Up @@ -71,9 +71,9 @@ public void robotPeriodic() {
// If any faults happen, print them out. Sticky faults will always be present if live-fault occurs
f_fusedSensorOutOfSync.refresh();
sf_fusedSensorOutOfSync.refresh();
f_missingRemoteSensor.refresh();
sf_missingRemoteSensor.refresh();
boolean anyFault = sf_fusedSensorOutOfSync.getValue() || sf_missingRemoteSensor.getValue();
f_remoteSensorInvalid.refresh();
sf_remoteSensorInvalid.refresh();
boolean anyFault = sf_fusedSensorOutOfSync.getValue() || sf_remoteSensorInvalid.getValue();
if(anyFault) {
System.out.println("A fault has occurred:");
/* If we're live, indicate live, otherwise if we're sticky indicate sticky, otherwise do nothing */
Expand All @@ -83,9 +83,9 @@ public void robotPeriodic() {
System.out.println("Fused sensor out of sync sticky-faulted");
}
/* If we're live, indicate live, otherwise if we're sticky indicate sticky, otherwise do nothing */
if(f_missingRemoteSensor.getValue()) {
if(f_remoteSensorInvalid.getValue()) {
System.out.println("Missing remote sensor live-faulted");
} else if (sf_missingRemoteSensor.getValue()) {
} else if (sf_remoteSensorInvalid.getValue()) {
System.out.println("Missing remote sensor sticky-faulted");
}
}
Expand Down
6 changes: 3 additions & 3 deletions java/FusedCANcoder/src/test/java/FusedCANcoderTests.java
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ public void testIndividualPos() {
/* Make sure both are initially set to 0 before messing with sim state */
retryConfigApply(()->talonSimState.setRawRotorPosition(0));
retryConfigApply(()->cancoderSimState.setRawPosition(0));
retryConfigApply(()->talon.setRotorPosition(0));
retryConfigApply(()->talon.setPosition(0));
retryConfigApply(()->cancoder.setPosition(0));
/* Wait for sets to take affect */
BaseStatusSignal.waitForAll(1.0, talonPos, cancoderPos);
Expand Down Expand Up @@ -90,7 +90,7 @@ public void testFusedCANcoderPos() {
/* Make sure both are initially set to 0 before messing with sim state */
retryConfigApply(()->talonSimState.setRawRotorPosition(0));
retryConfigApply(()->cancoderSimState.setRawPosition(0));
retryConfigApply(()->talon.setRotorPosition(0));
retryConfigApply(()->talon.setPosition(0));
retryConfigApply(()->cancoder.setPosition(0));
/* Wait for sets to take affect */
BaseStatusSignal.waitForAll(1.0, talonPos, cancoderPos);
Expand Down Expand Up @@ -134,7 +134,7 @@ public void testRemoteCANcoderPos() {
/* Make sure both are initially set to 0 before messing with sim state */
retryConfigApply(()->talonSimState.setRawRotorPosition(0));
retryConfigApply(()->cancoderSimState.setRawPosition(0));
retryConfigApply(()->talon.setRotorPosition(0));
retryConfigApply(()->talon.setPosition(0));
retryConfigApply(()->cancoder.setPosition(0));
/* Wait for sets to take affect */
BaseStatusSignal.waitForAll(1.0, talonPos, cancoderPos);
Expand Down
2 changes: 1 addition & 1 deletion java/MotionMagic/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ public void teleopPeriodic() {

m_motor.setControl(m_mmReq.withPosition(leftY * 10).withSlot(0));
if(m_joystick.getBButton()) {
m_motor.setRotorPosition(1);
m_motor.setPosition(1);
}
}

Expand Down
6 changes: 3 additions & 3 deletions java/PositionClosedLoop/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@ public class Robot extends TimedRobot {

/* Be able to switch which control request to use based on a button press */
/* Start at position 0, enable FOC, no feed forward, use slot 0 */
private final PositionVoltage m_voltagePosition = new PositionVoltage(0, true, 0, 0, false);
private final PositionVoltage m_voltagePosition = new PositionVoltage(0, 0, true, 0, 0, false);
/* Start at position 0, no feed forward, use slot 1 */
private final PositionTorqueCurrentFOC m_torquePosition = new PositionTorqueCurrentFOC(0, 0, 1, false);
private final PositionTorqueCurrentFOC m_torquePosition = new PositionTorqueCurrentFOC(0, 0, 0, 1, false);
/* Keep a brake request so we can disable the motor */
private final NeutralOut m_brake = new NeutralOut();

Expand Down Expand Up @@ -63,7 +63,7 @@ public void robotInit() {
}

/* Make sure we start at 0 */
m_fx.setRotorPosition(0);
m_fx.setPosition(0);
}

@Override
Expand Down
4 changes: 2 additions & 2 deletions java/VelocityClosedLoop/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,9 @@ public class Robot extends TimedRobot {

/* Be able to switch which control request to use based on a button press */
/* Start at velocity 0, enable FOC, no feed forward, use slot 0 */
private final VelocityVoltage m_voltageVelocity = new VelocityVoltage(0, true, 0, 0, false);
private final VelocityVoltage m_voltageVelocity = new VelocityVoltage(0, 0, true, 0, 0, false);
/* Start at velocity 0, no feed forward, use slot 1 */
private final VelocityTorqueCurrentFOC m_torqueVelocity = new VelocityTorqueCurrentFOC(0, 0, 1, false);
private final VelocityTorqueCurrentFOC m_torqueVelocity = new VelocityTorqueCurrentFOC(0, 0, 0, 1, false);
/* Keep a neutral out so we can disable the motor */
private final NeutralOut m_brake = new NeutralOut();

Expand Down
8 changes: 4 additions & 4 deletions java/WaitForAll/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -81,31 +81,31 @@ public void robotPeriodic() {
var status = BaseStatusSignal.waitForAll(m_waitForAllTimeout, m_lotsOfSignals);
System.out.println("Status of waiting on signals (normal use case): " + status);
for(var sig : m_lotsOfSignals) {
System.out.println("Signal status: " + sig.getError());
System.out.println("Signal status: " + sig.getStatus());
}
}
/* If we press the B button, test what happens when we wait on signals from different busses */
if(m_joystick.getBButtonPressed()) {
var status = BaseStatusSignal.waitForAll(m_waitForAllTimeout, m_signalsAcrossCANbuses);
System.out.println("Status of waiting on signals across different CAN busses: " + status);
for(var sig : m_signalsAcrossCANbuses) {
System.out.println("Signal status: " + sig.getError());
System.out.println("Signal status: " + sig.getStatus());
}
}
/* If we press the Y button, test what happens when we wait on no signals */
if(m_joystick.getYButtonPressed()) {
var status = BaseStatusSignal.waitForAll(m_waitForAllTimeout, m_noSignals);
System.out.println("Status of waiting on no signals: " + status);
for(var sig : m_noSignals) {
System.out.println("Signal status: " + sig.getError());
System.out.println("Signal status: " + sig.getStatus());
}
}
/* If we press the X button, test what happens when we wait on signals with the transcient motor controller */
if(m_joystick.getXButtonPressed()) {
var status = BaseStatusSignal.waitForAll(m_waitForAllTimeout, m_tanscientSignals);
System.out.println("Status of waiting on transcient signals: " + status);
for(var sig : m_tanscientSignals) {
System.out.println("Signal status: " + sig.getError());
System.out.println("Signal status: " + sig.getStatus());
}
}
}
Expand Down

0 comments on commit 5fa6ba7

Please sign in to comment.