From 5fa6ba7789952b97305807c36d04dd21fa24fb4b Mon Sep 17 00:00:00 2001 From: CoryNessCTR Date: Thu, 19 Oct 2023 13:09:24 -0400 Subject: [PATCH] Update code to use new Phoenix/WPILib beta features --- cpp/CommandBasedDrive/.vscode/settings.json | 5 ++++- .../src/main/cpp/RobotContainer.cpp | 8 +++++++- .../src/main/cpp/subsystems/DriveSubsystem.cpp | 4 ++-- .../src/main/include/RobotContainer.h | 7 ------- cpp/FusedCANcoder/src/main/cpp/Robot.cpp | 10 +++++----- cpp/FusedCANcoder/src/main/include/Robot.h | 4 ++-- cpp/PositionClosedLoop/src/main/cpp/Robot.cpp | 2 +- cpp/PositionClosedLoop/src/main/include/Robot.h | 4 ++-- cpp/VelocityClosedLoop/src/main/include/Robot.h | 4 ++-- cpp/WaitForAll/src/main/cpp/Robot.cpp | 8 ++++---- .../src/test/java/LatencyCompensationTests.java | 2 +- .../java/frc/robot/subsystems/DriveSubsystem.java | 4 ++-- .../src/main/java/frc/robot/Robot.java | 14 +++++++------- .../src/test/java/FusedCANcoderTests.java | 6 +++--- .../MotionMagic/src/main/java/frc/robot/Robot.java | 2 +- .../src/main/java/frc/robot/Robot.java | 6 +++--- .../src/main/java/frc/robot/Robot.java | 4 ++-- java/WaitForAll/src/main/java/frc/robot/Robot.java | 8 ++++---- 18 files changed, 52 insertions(+), 50 deletions(-) diff --git a/cpp/CommandBasedDrive/.vscode/settings.json b/cpp/CommandBasedDrive/.vscode/settings.json index d2d2fe11..fce7893c 100644 --- a/cpp/CommandBasedDrive/.vscode/settings.json +++ b/cpp/CommandBasedDrive/.vscode/settings.json @@ -14,5 +14,8 @@ "**/.factorypath": true, "**/*~": true }, - "C_Cpp.default.configurationProvider": "vscode-wpilib" + "C_Cpp.default.configurationProvider": "vscode-wpilib", + "files.associations": { + "concepts": "cpp" + } } diff --git a/cpp/CommandBasedDrive/src/main/cpp/RobotContainer.cpp b/cpp/CommandBasedDrive/src/main/cpp/RobotContainer.cpp index 82c5c555..15d6defb 100644 --- a/cpp/CommandBasedDrive/src/main/cpp/RobotContainer.cpp +++ b/cpp/CommandBasedDrive/src/main/cpp/RobotContainer.cpp @@ -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(); diff --git a/cpp/CommandBasedDrive/src/main/cpp/subsystems/DriveSubsystem.cpp b/cpp/CommandBasedDrive/src/main/cpp/subsystems/DriveSubsystem.cpp index 9a613d31..bcdfae60 100644 --- a/cpp/CommandBasedDrive/src/main/cpp/subsystems/DriveSubsystem.cpp +++ b/cpp/CommandBasedDrive/src/main/cpp/subsystems/DriveSubsystem.cpp @@ -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) { @@ -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) { diff --git a/cpp/CommandBasedDrive/src/main/include/RobotContainer.h b/cpp/CommandBasedDrive/src/main/include/RobotContainer.h index 47ca3210..fb2efa6c 100644 --- a/cpp/CommandBasedDrive/src/main/include/RobotContainer.h +++ b/cpp/CommandBasedDrive/src/main/include/RobotContainer.h @@ -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(); }}; diff --git a/cpp/FusedCANcoder/src/main/cpp/Robot.cpp b/cpp/FusedCANcoder/src/main/cpp/Robot.cpp index f26231b5..429ee6f7 100644 --- a/cpp/FusedCANcoder/src/main/cpp/Robot.cpp +++ b/cpp/FusedCANcoder/src/main/cpp/Robot.cpp @@ -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 */ @@ -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; } } diff --git a/cpp/FusedCANcoder/src/main/include/Robot.h b/cpp/FusedCANcoder/src/main/include/Robot.h index 334068c6..aab419c7 100644 --- a/cpp/FusedCANcoder/src/main/include/Robot.h +++ b/cpp/FusedCANcoder/src/main/include/Robot.h @@ -34,8 +34,8 @@ class Robot : public frc::TimedRobot { ctre::phoenix6::hardware::CANcoder m_cc{1, "fred"}; ctre::phoenix6::StatusSignal f_fusedSensorOutOfSync = m_fx.GetFault_FusedSensorOutOfSync(); ctre::phoenix6::StatusSignal sf_fusedSensorOutOfSync = m_fx.GetStickyFault_FusedSensorOutOfSync(); - ctre::phoenix6::StatusSignal f_missingRemoteSensor = m_fx.GetFault_MissingRemoteSensor(); - ctre::phoenix6::StatusSignal sf_missingRemoteSensor = m_fx.GetStickyFault_MissingRemoteSensor(); + ctre::phoenix6::StatusSignal f_remoteSensorInvalid = m_fx.GetFault_RemoteSensorDataInvalid(); + ctre::phoenix6::StatusSignal sf_remoteSensorInvalid = m_fx.GetStickyFault_RemoteSensorDataInvalid(); ctre::phoenix6::StatusSignal fx_pos = m_fx.GetPosition(); ctre::phoenix6::StatusSignal fx_vel = m_fx.GetVelocity(); diff --git a/cpp/PositionClosedLoop/src/main/cpp/Robot.cpp b/cpp/PositionClosedLoop/src/main/cpp/Robot.cpp index f2ae8eea..56e4b4f7 100644 --- a/cpp/PositionClosedLoop/src/main/cpp/Robot.cpp +++ b/cpp/PositionClosedLoop/src/main/cpp/Robot.cpp @@ -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() {} diff --git a/cpp/PositionClosedLoop/src/main/include/Robot.h b/cpp/PositionClosedLoop/src/main/include/Robot.h index 990e9de5..f534bb01 100644 --- a/cpp/PositionClosedLoop/src/main/include/Robot.h +++ b/cpp/PositionClosedLoop/src/main/include/Robot.h @@ -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}; diff --git a/cpp/VelocityClosedLoop/src/main/include/Robot.h b/cpp/VelocityClosedLoop/src/main/include/Robot.h index 30f31a25..7b0b9132 100644 --- a/cpp/VelocityClosedLoop/src/main/include/Robot.h +++ b/cpp/VelocityClosedLoop/src/main/include/Robot.h @@ -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}; diff --git a/cpp/WaitForAll/src/main/cpp/Robot.cpp b/cpp/WaitForAll/src/main/cpp/Robot.cpp index bae20ff5..306a95b8 100644 --- a/cpp/WaitForAll/src/main/cpp/Robot.cpp +++ b/cpp/WaitForAll/src/main/cpp/Robot.cpp @@ -22,7 +22,7 @@ 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 */ @@ -30,7 +30,7 @@ void Robot::RobotPeriodic() { 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 */ @@ -38,7 +38,7 @@ void Robot::RobotPeriodic() { 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 */ @@ -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; } } } diff --git a/java/BasicLatencyCompensation/src/test/java/LatencyCompensationTests.java b/java/BasicLatencyCompensation/src/test/java/LatencyCompensationTests.java index 13ee3f15..4816b4fe 100644 --- a/java/BasicLatencyCompensation/src/test/java/LatencyCompensationTests.java +++ b/java/BasicLatencyCompensation/src/test/java/LatencyCompensationTests.java @@ -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 */ diff --git a/java/CommandBasedDrive/src/main/java/frc/robot/subsystems/DriveSubsystem.java b/java/CommandBasedDrive/src/main/java/frc/robot/subsystems/DriveSubsystem.java index 94bae4a1..80019a3d 100644 --- a/java/CommandBasedDrive/src/main/java/frc/robot/subsystems/DriveSubsystem.java +++ b/java/CommandBasedDrive/src/main/java/frc/robot/subsystems/DriveSubsystem.java @@ -254,7 +254,7 @@ private void initializeLeftDriveTalonFX(TalonFXConfigurator cfg) { cfg.apply(toApply); /* And initialize position to 0 */ - cfg.setRotorPosition(0); + cfg.setPosition(0); } /** @@ -273,7 +273,7 @@ private void initializeRightDriveTalonFX(TalonFXConfigurator cfg) { cfg.apply(toApply); /* And initialize position to 0 */ - cfg.setRotorPosition(0); + cfg.setPosition(0); } /** diff --git a/java/FusedCANcoder/src/main/java/frc/robot/Robot.java b/java/FusedCANcoder/src/main/java/frc/robot/Robot.java index 8e14d017..5c54bd29 100644 --- a/java/FusedCANcoder/src/main/java/frc/robot/Robot.java +++ b/java/FusedCANcoder/src/main/java/frc/robot/Robot.java @@ -28,8 +28,8 @@ public class Robot extends TimedRobot { CANcoder m_cc = new CANcoder(1, "fred"); StatusSignal f_fusedSensorOutOfSync = m_fx.getFault_FusedSensorOutOfSync(); StatusSignal sf_fusedSensorOutOfSync = m_fx.getStickyFault_FusedSensorOutOfSync(); - StatusSignal f_missingRemoteSensor = m_fx.getFault_MissingRemoteSensor(); - StatusSignal sf_missingRemoteSensor = m_fx.getStickyFault_MissingRemoteSensor(); + StatusSignal f_remoteSensorInvalid = m_fx.getFault_RemoteSensorDataInvalid(); + StatusSignal sf_remoteSensorInvalid = m_fx.getStickyFault_RemoteSensorDataInvalid(); StatusSignal fx_pos = m_fx.getPosition(); StatusSignal fx_vel = m_fx.getVelocity(); @@ -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 */ @@ -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"); } } diff --git a/java/FusedCANcoder/src/test/java/FusedCANcoderTests.java b/java/FusedCANcoder/src/test/java/FusedCANcoderTests.java index 94f596ce..2ddb1961 100644 --- a/java/FusedCANcoder/src/test/java/FusedCANcoderTests.java +++ b/java/FusedCANcoder/src/test/java/FusedCANcoderTests.java @@ -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); @@ -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); @@ -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); diff --git a/java/MotionMagic/src/main/java/frc/robot/Robot.java b/java/MotionMagic/src/main/java/frc/robot/Robot.java index db28b0f4..b56a67f7 100644 --- a/java/MotionMagic/src/main/java/frc/robot/Robot.java +++ b/java/MotionMagic/src/main/java/frc/robot/Robot.java @@ -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); } } diff --git a/java/PositionClosedLoop/src/main/java/frc/robot/Robot.java b/java/PositionClosedLoop/src/main/java/frc/robot/Robot.java index 7d7700ff..847e6eb3 100644 --- a/java/PositionClosedLoop/src/main/java/frc/robot/Robot.java +++ b/java/PositionClosedLoop/src/main/java/frc/robot/Robot.java @@ -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(); @@ -63,7 +63,7 @@ public void robotInit() { } /* Make sure we start at 0 */ - m_fx.setRotorPosition(0); + m_fx.setPosition(0); } @Override diff --git a/java/VelocityClosedLoop/src/main/java/frc/robot/Robot.java b/java/VelocityClosedLoop/src/main/java/frc/robot/Robot.java index c63a2dad..a025f9ce 100644 --- a/java/VelocityClosedLoop/src/main/java/frc/robot/Robot.java +++ b/java/VelocityClosedLoop/src/main/java/frc/robot/Robot.java @@ -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(); diff --git a/java/WaitForAll/src/main/java/frc/robot/Robot.java b/java/WaitForAll/src/main/java/frc/robot/Robot.java index 683d92a9..b5788878 100644 --- a/java/WaitForAll/src/main/java/frc/robot/Robot.java +++ b/java/WaitForAll/src/main/java/frc/robot/Robot.java @@ -81,7 +81,7 @@ 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 */ @@ -89,7 +89,7 @@ public void robotPeriodic() { 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 */ @@ -97,7 +97,7 @@ public void robotPeriodic() { 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 */ @@ -105,7 +105,7 @@ public void robotPeriodic() { 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()); } } }