Skip to content

Commit

Permalink
Clean up all C++ and Python examples
Browse files Browse the repository at this point in the history
  • Loading branch information
bhall-ctre committed Oct 31, 2024
1 parent 5f5f808 commit 41ecc8a
Show file tree
Hide file tree
Showing 27 changed files with 179 additions and 165 deletions.
11 changes: 5 additions & 6 deletions cpp/ArcadeDrive/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@ void Robot::RobotInit() {
configs::TalonFXConfiguration rightConfiguration{};

/* User can optionally change the configs, or leave it alone to perform a factory default */
leftConfiguration.MotorOutput.Inverted = false;
rightConfiguration.MotorOutput.Inverted = true;
leftConfiguration.MotorOutput.Inverted = signals::InvertedValue::CounterClockwise_Positive;
rightConfiguration.MotorOutput.Inverted = signals::InvertedValue::Clockwise_Positive;

leftLeader.GetConfigurator().Apply(leftConfiguration);
leftFollower.GetConfigurator().Apply(leftConfiguration);
Expand All @@ -25,9 +25,9 @@ void Robot::RobotInit() {
leftFollower.SetControl(controls::Follower{leftLeader.GetDeviceID(), false});
rightFollower.SetControl(controls::Follower{rightLeader.GetDeviceID(), false});
}

void Robot::RobotPeriodic() {
if (++printCount >= 10)
{
if (++printCount >= 10) {
printCount = 0;
std::cout << "Left out: " << leftLeader.Get() << std::endl;
std::cout << "Right out: " << rightLeader.Get() << std::endl;
Expand All @@ -48,8 +48,7 @@ void Robot::TeleopPeriodic() {
/* Set output to control frames */
leftOut.Output = fwd + rot;
rightOut.Output = fwd - rot;
if (!joystick.GetAButton())
{
if (!joystick.GetAButton()) {
/* And set them to the motors */
leftLeader.SetControl(leftOut);
rightLeader.SetControl(rightOut);
Expand Down
10 changes: 5 additions & 5 deletions cpp/ArcadeDrive/src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,12 @@

class Robot : public frc::TimedRobot {
private:
static constexpr char const *CANBUS_NAME{"rio"};
ctre::phoenix6::CANBus kCANBus{"rio"};

ctre::phoenix6::hardware::TalonFX leftLeader{1, CANBUS_NAME};
ctre::phoenix6::hardware::TalonFX leftFollower{2, CANBUS_NAME};
ctre::phoenix6::hardware::TalonFX rightLeader{3, CANBUS_NAME};
ctre::phoenix6::hardware::TalonFX rightFollower{4, CANBUS_NAME};
ctre::phoenix6::hardware::TalonFX leftLeader{1, kCANBus};
ctre::phoenix6::hardware::TalonFX leftFollower{2, kCANBus};
ctre::phoenix6::hardware::TalonFX rightLeader{3, kCANBus};
ctre::phoenix6::hardware::TalonFX rightFollower{4, kCANBus};

ctre::phoenix6::controls::DutyCycleOut leftOut{0}; // Initialize output to 0%
ctre::phoenix6::controls::DutyCycleOut rightOut{0}; // Initialize output to 0%
Expand Down
2 changes: 1 addition & 1 deletion cpp/BasicLatencyCompensation/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ void Robot::RobotPeriodic() {
auto p2CompensatedYaw = BaseStatusSignal::GetLatencyCompensatedValue(m_p2yaw, m_p2yawRate);

/* Print out both values so it shows how they perform */
if (m_printCount++ > 10 && m_joystick.GetAButton()) {
if (++m_printCount >= 10 && m_joystick.GetAButton()) {
m_printCount = 0;
printf("CANcoder: Pos: %10.3f - Latency-Compensated: %10.3f - Difference: %6.5f\n", m_ccpos.GetValue().value(), ccCompensatedPos.value(), (m_ccpos.GetValue() - ccCompensatedPos).value());
printf("Talon FX: Pos: %10.3f - Latency-Compensated: %10.3f - Difference: %6.5f\n", m_fxpos.GetValue().value(), fxCompensatedPos.value(), (m_fxpos.GetValue() - fxCompensatedPos).value());
Expand Down
7 changes: 4 additions & 3 deletions cpp/CANcoder/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,9 @@ void Robot::RobotInit() {
}
void Robot::RobotPeriodic() {
/* Every print_period get the CANcoder position/velocity and report it */
if (frc::Timer::GetFPGATimestamp() - currentTime > print_period) {
if (frc::Timer::GetFPGATimestamp() - currentTime >= print_period) {
currentTime += print_period;

/**
* GetPosition automatically calls Refresh(), no need to manually refresh.
*
Expand All @@ -34,9 +35,9 @@ void Robot::RobotPeriodic() {
std::cout << "Position is " << pos << " with " << pos.GetTimestamp().GetLatency().value() << " seconds of latency" << std::endl;

/**
* Get the velocity StatusSignalValue
* Get the velocity StatusSignalValue without refreshing
*/
auto &vel = cancoder.GetVelocity();
auto &vel = cancoder.GetVelocity(false);
/* This time wait for the signal to reduce latency */
vel.WaitForUpdate(print_period); // Wait up to our period
/**
Expand Down
6 changes: 3 additions & 3 deletions cpp/CommandBasedDrive/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ void Robot::DisabledPeriodic() {}
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();

if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Schedule();
}
}
Expand All @@ -49,9 +49,9 @@ void Robot::TeleopInit() {
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
if (m_autonomousCommand) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
m_autonomousCommand = std::nullopt;
}
}

Expand Down
27 changes: 15 additions & 12 deletions cpp/CommandBasedDrive/src/main/cpp/RobotContainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,17 @@

#include "RobotContainer.h"
#include <frc2/command/button/Trigger.h>
#include <frc2/command/Commands.h>

RobotContainer::RobotContainer()
{
// Initialize all of your commands and subsystems here
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));
m_driveSubsystem.SetDefaultCommand(
m_driveSubsystem.Run([this] {
/* invert the joystick Y because forward Y is negative */
m_driveSubsystem.ArcadeDrive(-m_joystick.GetLeftY(), m_joystick.GetRightX());
})
);

// Configure the button bindings
ConfigureButtonBindings();
Expand All @@ -23,13 +23,16 @@ RobotContainer::RobotContainer()
void RobotContainer::ConfigureButtonBindings()
{
// Configure your button bindings here
frc2::Trigger{[this]()
{ return m_joystick.GetLeftBumperButton(); }}
.WhileTrue(&m_driveStraightCommand);
m_joystick.LeftBumper().WhileTrue(
DriveStraightCommand{
m_driveSubsystem,
[this] { return -m_joystick.GetLeftY(); }
}.ToPtr()
);
}

frc2::Command *RobotContainer::GetAutonomousCommand()
frc2::CommandPtr RobotContainer::GetAutonomousCommand()
{
// An example command will be run in autonomous
return nullptr;
return frc2::cmd::Print("No autonomous command configured");
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,12 @@

#include "commands/DriveStraightCommand.h"

DriveStraightCommand::DriveStraightCommand(DriveSubsystem &subsystem,
std::function<double()> throttle) : m_driveSubsystem{subsystem},
m_throttle{std::move(throttle)},
m_yawGetter{subsystem.GetYaw()},
m_holdYaw{0},
m_driveStraightThread{[this]()
{ DriveStraightExecution(); }}
DriveStraightCommand::DriveStraightCommand(DriveSubsystem &subsystem, std::function<double()> throttle) :
m_driveSubsystem{subsystem},
m_throttle{std::move(throttle)},
m_yawGetter{subsystem.GetYaw()},
m_holdYaw{0_deg},
m_driveStraightThread{[this] { DriveStraightExecution(); }}
{
AddRequirements(&subsystem);
}
Expand Down
14 changes: 9 additions & 5 deletions cpp/CommandBasedDrive/src/main/cpp/subsystems/DriveSubsystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,9 +99,11 @@ void DriveSubsystem::Periodic()
* in the previous article while in simulation, but will use
* real values on the robot itself.
*/
m_odometry.Update(m_pigeon2.GetRotation2d(),
rotationsToMeters(m_leftLeader.GetPosition().GetValue()),
rotationsToMeters(m_rightLeader.GetPosition().GetValue()));
m_odometry.Update(
m_pigeon2.GetRotation2d(),
rotationsToMeters(m_leftLeader.GetPosition().GetValue()),
rotationsToMeters(m_rightLeader.GetPosition().GetValue())
);
m_field.SetRobotPose(m_odometry.GetPose());
}

Expand All @@ -124,8 +126,10 @@ void DriveSubsystem::SimulationPeriodic()
* WPILib expects +V to be forward. We have already configured
* our orientations to match this behavior.
*/
m_driveSim.SetInputs(m_leftSimState.GetMotorVoltage(),
m_rightSimState.GetMotorVoltage());
m_driveSim.SetInputs(
m_leftSimState.GetMotorVoltage(),
m_rightSimState.GetMotorVoltage()
);

/*
* Advance the model by 20 ms. Note that if you are running this
Expand Down
2 changes: 1 addition & 1 deletion cpp/CommandBasedDrive/src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class Robot : public frc::TimedRobot {
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
std::optional<frc2::CommandPtr> m_autonomousCommand;

RobotContainer m_container;
};
18 changes: 8 additions & 10 deletions cpp/CommandBasedDrive/src/main/include/RobotContainer.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

#include <frc2/command/Command.h>
#include <frc2/command/RunCommand.h>
#include <frc/XboxController.h>
#include <frc2/command/button/CommandXboxController.h>
#include "subsystems/DriveSubsystem.h"
#include "commands/DriveStraightCommand.h"

Expand All @@ -19,19 +19,17 @@
*/
class RobotContainer
{
private:
// The robot's subsystems and joysticks are defined here...
frc2::CommandXboxController m_joystick{0};

public:
DriveSubsystem m_driveSubsystem{};

RobotContainer();

frc2::Command *GetAutonomousCommand();
frc2::CommandPtr GetAutonomousCommand();

private:
// The robot's subsystems and commands are defined here...
frc::XboxController m_joystick{0};

DriveSubsystem m_driveSubsystem{};
DriveStraightCommand m_driveStraightCommand{m_driveSubsystem,
[this]()
{ return -m_joystick.GetLeftY(); }};

void ConfigureButtonBindings();
};
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
#include <frc/Notifier.h>
#include <units/time.h>

class DriveStraightCommand
: public frc2::CommandHelper<frc2::Command, DriveStraightCommand> {
class DriveStraightCommand : public frc2::CommandHelper<frc2::Command, DriveStraightCommand>
{
private:
static constexpr units::time::second_t MAX_UPDATE_PERIOD{0.050_s};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class DriveSubsystem : public frc2::SubsystemBase
static constexpr units::inch_t kWheelRadiusInches = 3_in;

frc::sim::DifferentialDrivetrainSim m_driveSim{
frc::DCMotor::Falcon500FOC(2),
frc::DCMotor::KrakenX60FOC(2),
kGearRatio,
2.1_kg_sq_m, // MOI of 2.1 kg m^2 (from CAD model)
26.5_kg, // Mass of robot is 26.5 kg
Expand Down
8 changes: 5 additions & 3 deletions cpp/ControlRequestLimits/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,11 @@ void Robot::AutonomousPeriodic() {}
void Robot::TeleopInit() {}
void Robot::TeleopPeriodic()
{
m_fx.SetControl(m_out.WithOutput(-m_joystick.GetLeftY())
.WithLimitForwardMotion(m_joystick.GetLeftBumper())
.WithLimitReverseMotion(m_joystick.GetRightBumper()));
m_fx.SetControl(
m_out.WithOutput(-m_joystick.GetLeftY())
.WithLimitForwardMotion(m_joystick.GetLeftBumper())
.WithLimitReverseMotion(m_joystick.GetRightBumper())
);
}

void Robot::DisabledInit() {}
Expand Down
5 changes: 3 additions & 2 deletions cpp/CurrentLimits/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,9 @@ void Robot::RobotPeriodic() {
std::cout << "Setting stator limit to " << m_currentLimits.StatorCurrentLimitEnable << std::endl;
m_fx.GetConfigurator().Apply(m_currentLimits);
}
if (printCount++ > 20) {
printCount= 0;

if (++printCount >= 20) {
printCount = 0;
std::cout << "Supply current: " << m_fx.GetSupplyCurrent() << std::endl;
std::cout << "Stator current: " << m_fx.GetStatorCurrent() << std::endl;
}
Expand Down
7 changes: 4 additions & 3 deletions cpp/FusedCANcoder/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ void Robot::RobotInit() {
m_fx.GetConfigurator().Apply(fx_cfg);
}
void Robot::RobotPeriodic() {
if (printCount++ > 10) {
if (++printCount >= 10) {
printCount = 0;

BaseStatusSignal::RefreshAll(
Expand All @@ -33,11 +33,12 @@ void Robot::RobotPeriodic() {
f_remoteSensorInvalid,
sf_remoteSensorInvalid,
fx_pos, fx_vel,
cc_pos, cc_vel);
cc_pos, cc_vel
);

// If any faults happen, print them out. Sticky faults will always be present if live-fault occurs
bool anyFault = sf_fusedSensorOutOfSync.GetValue() || sf_remoteSensorInvalid.GetValue();
if(anyFault) {
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 */
if (f_fusedSensorOutOfSync.GetValue()) {
Expand Down
18 changes: 9 additions & 9 deletions cpp/FusedCANcoder/src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,15 @@
class Robot : public frc::TimedRobot {
ctre::phoenix6::hardware::TalonFX m_fx{1, "canivore"};
ctre::phoenix6::hardware::CANcoder m_cc{1, "canivore"};
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_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();
ctre::phoenix6::StatusSignal<units::turn_t> &cc_pos = m_cc.GetPosition();
ctre::phoenix6::StatusSignal<units::turns_per_second_t> &cc_vel = m_cc.GetVelocity();
ctre::phoenix6::StatusSignal<bool> &f_fusedSensorOutOfSync = m_fx.GetFault_FusedSensorOutOfSync(false);
ctre::phoenix6::StatusSignal<bool> &sf_fusedSensorOutOfSync = m_fx.GetStickyFault_FusedSensorOutOfSync(false);
ctre::phoenix6::StatusSignal<bool> &f_remoteSensorInvalid = m_fx.GetFault_RemoteSensorDataInvalid(false);
ctre::phoenix6::StatusSignal<bool> &sf_remoteSensorInvalid = m_fx.GetStickyFault_RemoteSensorDataInvalid(false);

ctre::phoenix6::StatusSignal<units::turn_t> &fx_pos = m_fx.GetPosition(false);
ctre::phoenix6::StatusSignal<units::turns_per_second_t> &fx_vel = m_fx.GetVelocity(false);
ctre::phoenix6::StatusSignal<units::turn_t> &cc_pos = m_cc.GetPosition(false);
ctre::phoenix6::StatusSignal<units::turns_per_second_t> &cc_vel = m_cc.GetVelocity(false);

ctre::phoenix6::controls::DutyCycleOut m_dutyCycleControl{0};

Expand Down
2 changes: 1 addition & 1 deletion cpp/MotionMagic/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ void Robot::RobotInit() {
}
}
void Robot::RobotPeriodic() {
if (m_printCount++ > 10) {
if (++m_printCount >= 10) {
m_printCount = 0;
std::cout << "Pos: " << m_motor.GetPosition() << std::endl;
std::cout << "Vel: " << m_motor.GetVelocity() << std::endl;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class FlywheelMechanism : public frc2::SubsystemBase
},
frc2::sysid::Mechanism{
[this](units::volt_t volts) { m_motorToTest.SetControl(m_sysIdControl.WithOutput(volts)); },
[](auto) {},
{},
this
}
};
Expand Down
7 changes: 4 additions & 3 deletions cpp/Pigeon2/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,9 @@ void Robot::RobotInit() {
}
void Robot::RobotPeriodic() {
/* Every print_period get the CANcoder position/velocity and report it */
if (frc::Timer::GetFPGATimestamp() - currentTime > print_period) {
if (frc::Timer::GetFPGATimestamp() - currentTime >= print_period) {
currentTime += print_period;

/**
* GetYaw automatically calls Refresh(), no need to manually refresh.
*
Expand All @@ -34,9 +35,9 @@ void Robot::RobotPeriodic() {
std::cout << "Yaw is " << yaw << " with " << yaw.GetTimestamp().GetLatency().value() << " seconds of latency" << std::endl;

/**
* Get the Gravity Vector Z component StatusSignalValue
* Get the Gravity Vector Z component StatusSignalValue without refreshing
*/
auto &gravityZ = pidgey.GetGravityVectorZ();
auto &gravityZ = pidgey.GetGravityVectorZ(false);
/* This time wait for the signal to reduce latency */
gravityZ.WaitForUpdate(print_period); // Wait up to our period
/**
Expand Down
Loading

0 comments on commit 41ecc8a

Please sign in to comment.