Skip to content

Commit

Permalink
Update all Java examples
Browse files Browse the repository at this point in the history
  • Loading branch information
bhall-ctre committed Oct 31, 2024
1 parent 102684d commit a53706d
Show file tree
Hide file tree
Showing 36 changed files with 333 additions and 270 deletions.
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 @@ -8,14 +8,15 @@
using namespace ctre::phoenix6;

void Robot::RobotInit() {
/* Configure the Talon to use a supply limit of 60 amps IF we exceed 80 amps for over 0.1 seconds */
/* Configure the Talon to use a supply limit of 70 A, and
* lower to 40 A if we're at 70 A for over 1 second */
configs::TalonFXConfiguration toConfigure{};
m_currentLimits.SupplyCurrentLimit = 70_A; // Default limit of 70 A
m_currentLimits.SupplyCurrentLowerLimit = 40_A; // Reduce the limit to 40 A if we've limited to 70 A...
m_currentLimits.SupplyCurrentLowerTime = 1_s; // ...for at least 1 second
m_currentLimits.SupplyCurrentLimitEnable = true; // And enable it

m_currentLimits.StatorCurrentLimit = 120_A; // Limit stator to 120 amps
m_currentLimits.StatorCurrentLimit = 120_A; // Limit stator to 120 A
m_currentLimits.StatorCurrentLimitEnable = true; // And enable it

toConfigure.CurrentLimits = m_currentLimits;
Expand Down
6 changes: 3 additions & 3 deletions cpp/MotionMagic/src/main/cpp/sim/PhysicsSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@

using namespace ctre::phoenix6;

void PhysicsSim::AddTalonFX(hardware::TalonFX& falcon, units::kilogram_square_meter_t rotorInertia) {
TalonFXSimProfile *simFalcon = new TalonFXSimProfile(falcon, rotorInertia);
_simProfiles.push_back(simFalcon);
void PhysicsSim::AddTalonFX(hardware::TalonFX& talonFX, units::kilogram_square_meter_t rotorInertia) {
TalonFXSimProfile *simTalonFX = new TalonFXSimProfile(talonFX, rotorInertia);
_simProfiles.push_back(simTalonFX);
}

void PhysicsSim::Run() {
Expand Down
14 changes: 7 additions & 7 deletions cpp/MotionMagic/src/main/cpp/sim/TalonFXSimProfile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,24 +3,24 @@

using namespace ctre::phoenix6;

TalonFXSimProfile::TalonFXSimProfile(hardware::TalonFX& falcon, units::kilogram_square_meter_t rotorInertia) :
TalonFXSimProfile::TalonFXSimProfile(hardware::TalonFX& talonFX, units::kilogram_square_meter_t rotorInertia) :
_motorSim{frc::LinearSystemId::DCMotorSystem(frc::DCMotor::KrakenX60FOC(1), rotorInertia, 1), frc::DCMotor::KrakenX60FOC(1)},
_falcon{falcon} {
}
_talonFXSim{talonFX.GetSimState()}
{}

void TalonFXSimProfile::Run() {
/// DEVICE SPEED SIMULATION

_motorSim.SetInputVoltage(_falcon.GetSimState().GetMotorVoltage());
_motorSim.SetInputVoltage(_talonFXSim.GetMotorVoltage());

_motorSim.Update(GetPeriod());

/// SET SIM PHYSICS INPUTS
auto const position = _motorSim.GetAngularPosition();
auto const velocity = _motorSim.GetAngularVelocity();

_falcon.GetSimState().SetRawRotorPosition(position);
_falcon.GetSimState().SetRotorVelocity(velocity);
_talonFXSim.SetRawRotorPosition(position);
_talonFXSim.SetRotorVelocity(velocity);

_falcon.GetSimState().SetSupplyVoltage(12_V - _falcon.GetSimState().GetSupplyCurrent() * kMotorResistance);
_talonFXSim.SetSupplyVoltage(12_V - _talonFXSim.GetSupplyCurrent() * kMotorResistance);
}
4 changes: 2 additions & 2 deletions cpp/MotionMagic/src/main/include/sim/PhysicsSim.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,12 @@ class PhysicsSim {
/**
* Adds a TalonFX controller to the simulator.
*
* @param falcon
* @param talonFX
* The TalonFX device
* @param rotorInertia
* Rotational Inertia of the mechanism at the rotor
*/
void AddTalonFX(ctre::phoenix6::hardware::TalonFX& falcon, units::kilogram_square_meter_t rotorInertia);
void AddTalonFX(ctre::phoenix6::hardware::TalonFX& talonFX, units::kilogram_square_meter_t rotorInertia);

/**
* Runs the simulator:
Expand Down
6 changes: 3 additions & 3 deletions cpp/MotionMagic/src/main/include/sim/TalonFXSimProfile.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,19 +11,19 @@
class TalonFXSimProfile : public SimProfile {
static constexpr units::ohm_t kMotorResistance = 2_mOhm; // Assume 2mOhm resistance for voltage drop calculation
frc::sim::DCMotorSim _motorSim;
ctre::phoenix6::hardware::TalonFX& _falcon;
ctre::phoenix6::sim::TalonFXSimState& _talonFXSim;


public:
/**
* Creates a new simulation profile for a TalonFX device.
*
* @param falcon
* @param talonFX
* The TalonFX device
* @param rotorInertia
* Rotational inertia at the Rotor
*/
TalonFXSimProfile(ctre::phoenix6::hardware::TalonFX& falcon, units::kilogram_square_meter_t rotorInertia);
TalonFXSimProfile(ctre::phoenix6::hardware::TalonFX& talonFX, units::kilogram_square_meter_t rotorInertia);

/**
* Runs the simulation profile.
Expand Down
2 changes: 1 addition & 1 deletion cpp/Simulation/src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class Robot : public frc::TimedRobot {
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
6 changes: 3 additions & 3 deletions cpp/WaitForAll/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ void Robot::RobotPeriodic() {
if (m_joystick.GetAButtonPressed()) {
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) {
for (auto const &sig : m_lotsOfSignals) {
std::cout << "Signal status: " << sig->GetStatus().GetName() << std::endl;
}
}
Expand All @@ -29,7 +29,7 @@ void Robot::RobotPeriodic() {
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) {
for (auto const& sig : m_signalsAcrossCANbuses) {
std::cout << "Signal status: " << sig->GetStatus().GetName() << std::endl;
}
}
Expand All @@ -38,7 +38,7 @@ void Robot::RobotPeriodic() {
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) {
for (auto const& sig : m_noSignals) {
std::cout << "Signal status: " << sig->GetStatus().GetName() << std::endl;
}
}
Expand Down
13 changes: 7 additions & 6 deletions java/ArcadeDrive/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

package frc.robot;

import com.ctre.phoenix6.Utils;
import com.ctre.phoenix6.CANBus;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.DutyCycleOut;
import com.ctre.phoenix6.controls.Follower;
Expand All @@ -21,11 +21,12 @@
* project.
*/
public class Robot extends TimedRobot {
private static final String CANBUS_NAME = "canivore";
private final TalonFX leftLeader = new TalonFX(1, CANBUS_NAME);
private final TalonFX leftFollower = new TalonFX(2, CANBUS_NAME);
private final TalonFX rightLeader = new TalonFX(3, CANBUS_NAME);
private final TalonFX rightFollower = new TalonFX(4, CANBUS_NAME);
private final CANBus kCANBus = new CANBus("canivore");

private final TalonFX leftLeader = new TalonFX(1, kCANBus);
private final TalonFX leftFollower = new TalonFX(2, kCANBus);
private final TalonFX rightLeader = new TalonFX(3, kCANBus);
private final TalonFX rightFollower = new TalonFX(4, kCANBus);

private final DutyCycleOut leftOut = new DutyCycleOut(0);
private final DutyCycleOut rightOut = new DutyCycleOut(0);
Expand Down
35 changes: 19 additions & 16 deletions java/BasicLatencyCompensation/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import static edu.wpi.first.units.Units.*;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.CANBus;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.controls.DutyCycleOut;
import com.ctre.phoenix6.hardware.CANcoder;
Expand All @@ -25,22 +26,24 @@
* project.
*/
public class Robot extends TimedRobot {
private static final String CANBUS_NAME = "canivore";
private final CANcoder m_cc = new CANcoder(0, CANBUS_NAME);
private final TalonFX m_fx = new TalonFX(0, CANBUS_NAME);
private final Pigeon2 m_p2 = new Pigeon2(0, CANBUS_NAME);
private final CANBus kCANBus = new CANBus("canivore");

private final CANcoder m_cc = new CANcoder(0, kCANBus);
private final TalonFX m_fx = new TalonFX(0, kCANBus);
private final Pigeon2 m_p2 = new Pigeon2(0, kCANBus);

private int m_printCount = 0;

private final DutyCycleOut m_dutycycle = new DutyCycleOut(0);

private final XboxController m_joystick = new XboxController(0);

private final StatusSignal<Angle> m_ccpos = m_cc.getPosition();
private final StatusSignal<Angle> m_fxpos = m_fx.getPosition();
private final StatusSignal<Angle> m_p2yaw = m_p2.getYaw();
private final StatusSignal<AngularVelocity> m_ccvel = m_cc.getVelocity();
private final StatusSignal<AngularVelocity> m_fxvel = m_fx.getVelocity();
private final StatusSignal<AngularVelocity> m_p2yawRate = m_p2.getAngularVelocityZWorld();
private final StatusSignal<Angle> m_ccpos = m_cc.getPosition(false);
private final StatusSignal<Angle> m_fxpos = m_fx.getPosition(false);
private final StatusSignal<Angle> m_p2yaw = m_p2.getYaw(false);
private final StatusSignal<AngularVelocity> m_ccvel = m_cc.getVelocity(false);
private final StatusSignal<AngularVelocity> m_fxvel = m_fx.getVelocity(false);
private final StatusSignal<AngularVelocity> m_p2yawRate = m_p2.getAngularVelocityZWorld(false);

/**
* This function is run when the robot is first started up and should be used for any
Expand All @@ -64,23 +67,23 @@ public void robotPeriodic() {
var 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;
System.out.printf(
"CANcoder: Pos: %10.3f - Latency-Compensated: %10.3f - Difference: %6.5f%n",
m_ccpos.getValue().in(Rotations),
ccCompensatedPos.in(Rotations),
m_ccpos.getValue().in(Rotations),
ccCompensatedPos.in(Rotations),
ccCompensatedPos.minus(m_ccpos.getValue()).in(Rotations)
);
System.out.printf(
"Talon FX: Pos: %10.3f - Latency-Compensated: %10.3f - Difference: %6.5f%n",
m_fxpos.getValue().in(Rotations), fxCompensatedPos.in(Rotations),
m_fxpos.getValue().in(Rotations), fxCompensatedPos.in(Rotations),
fxCompensatedPos.minus(m_fxpos.getValue()).in(Rotations)
);
System.out.printf(
"Pigeon2 : Yaw: %10.3f - Latency-Compensated: %10.3f - Difference: %6.5f%n",
m_p2yaw.getValue().in(Degrees),
p2CompensatedYaw.in(Degrees),
m_p2yaw.getValue().in(Degrees),
p2CompensatedYaw.in(Degrees),
p2CompensatedYaw.minus(m_p2yaw.getValue()).in(Degrees)
);
System.out.println();
Expand Down
23 changes: 14 additions & 9 deletions java/CANcoder/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import static edu.wpi.first.units.Units.*;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.CANBus;
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.controls.DutyCycleOut;
import com.ctre.phoenix6.hardware.CANcoder;
Expand All @@ -26,9 +27,11 @@
public class Robot extends TimedRobot {
private static final double PRINT_PERIOD = 0.5; // Update every 500 ms

private static final String canBusName = "rio";
private final TalonFX talonFX = new TalonFX(2, canBusName);
private final CANcoder cancoder = new CANcoder(1, canBusName);
private final CANBus kCANBus = new CANBus("rio");

private final TalonFX talonFX = new TalonFX(2, kCANBus);
private final CANcoder cancoder = new CANcoder(1, kCANBus);

private final DutyCycleOut fwdOut = new DutyCycleOut(0);
private final XboxController controller = new XboxController(0);

Expand Down Expand Up @@ -67,19 +70,21 @@ public void robotPeriodic() {
System.out.println("Position is " + pos.toString() + " with " + pos.getTimestamp().getLatency() + " seconds of latency");

/**
* Get the velocity StatusSignalValue
* Get the velocity StatusSignalValue without refreshing
*/
var vel = cancoder.getVelocity();
var vel = cancoder.getVelocity(false);
/* This time wait for the signal to reduce latency */
vel.waitForUpdate(PRINT_PERIOD); // Wait up to our period
/**
* This uses the explicit getValue and getUnits functions to print, even though it's not
* necessary for the ostream print
*/
System.out.println("Velocity is " +
vel.getValue() + " " +
vel.getUnits() + " with " +
vel.getTimestamp().getLatency() + " seconds of latency");
System.out.println(
"Velocity is " +
vel.getValue() + " " +
vel.getUnits() + " with " +
vel.getTimestamp().getLatency() + " seconds of latency"
);
/**
* Notice when running this example that the second print's latency is always shorter than the first print's latency.
* This is because we explicitly wait for the signal using the waitForUpdate() method instead of using the refresh()
Expand Down
10 changes: 5 additions & 5 deletions java/CANcoder/src/main/java/frc/robot/sim/PhysicsSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public static PhysicsSim getInstance() {
/**
* Adds a TalonFX controller to the simulator.
*
* @param falcon
* @param talonFX
* The TalonFX device
* @param can
* The CANcoder device
Expand All @@ -31,10 +31,10 @@ public static PhysicsSim getInstance() {
* @param rotorInertia
* Rotational Inertia of the mechanism at the rotor
*/
public void addTalonFX(TalonFX falcon, CANcoder can, double gearRatio, final double rotorInertia) {
if (falcon != null) {
TalonFXSimProfile simFalcon = new TalonFXSimProfile(falcon, can, gearRatio, rotorInertia);
_simProfiles.add(simFalcon);
public void addTalonFX(TalonFX talonFX, CANcoder can, double gearRatio, final double rotorInertia) {
if (talonFX != null) {
TalonFXSimProfile simTalonFX = new TalonFXSimProfile(talonFX, can, gearRatio, rotorInertia);
_simProfiles.add(simTalonFX);
}
}

Expand Down
17 changes: 9 additions & 8 deletions java/CANcoder/src/main/java/frc/robot/sim/TalonFXSimProfile.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.sim.TalonFXSimState;

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;
Expand All @@ -14,7 +15,7 @@
*/
class TalonFXSimProfile extends SimProfile {
private static final double kMotorResistance = 0.002; // Assume 2mOhm resistance for voltage drop calculation
private final TalonFX _falcon;
private final TalonFXSimState _talonFXSim;
private final CANcoder _canCoder;
private final double _gearRatio;

Expand All @@ -23,7 +24,7 @@ class TalonFXSimProfile extends SimProfile {
/**
* Creates a new simulation profile for a TalonFX device.
*
* @param falcon
* @param talonFX
* The TalonFX device
* @param canCoder
* The CANcoder associated with the TalonFX
Expand All @@ -32,8 +33,8 @@ class TalonFXSimProfile extends SimProfile {
* @param rotorInertia
* Rotational Inertia of the mechanism at the rotor
*/
public TalonFXSimProfile(final TalonFX falcon, final CANcoder canCoder, final double gearRatio, final double rotorInertia) {
this._falcon = falcon;
public TalonFXSimProfile(final TalonFX talonFX, final CANcoder canCoder, final double gearRatio, final double rotorInertia) {
this._talonFXSim = talonFX.getSimState();
this._canCoder = canCoder;
this._gearRatio = gearRatio;

Expand All @@ -50,18 +51,18 @@ public TalonFXSimProfile(final TalonFX falcon, final CANcoder canCoder, final do
*/
public void run() {
// DEVICE SPEED SIMULATION
_motorSim.setInputVoltage(_falcon.getSimState().getMotorVoltage());
_motorSim.setInputVoltage(_talonFXSim.getMotorVoltage());

_motorSim.update(getPeriod());

// SET SIM PHYSICS INPUTS
final double position_rot = _motorSim.getAngularPositionRotations() * _gearRatio;
final double velocity_rps = Units.radiansToRotations(_motorSim.getAngularVelocityRadPerSec()) * _gearRatio;

_falcon.getSimState().setRawRotorPosition(position_rot);
_falcon.getSimState().setRotorVelocity(velocity_rps);
_talonFXSim.setRawRotorPosition(position_rot);
_talonFXSim.setRotorVelocity(velocity_rps);

_falcon.getSimState().setSupplyVoltage(12 - _falcon.getSimState().getSupplyCurrent() * kMotorResistance);
_talonFXSim.setSupplyVoltage(12 - _talonFXSim.getSupplyCurrent() * kMotorResistance);

_canCoder.getSimState().setRawPosition(position_rot / _gearRatio);
_canCoder.getSimState().setVelocity(velocity_rps / _gearRatio);
Expand Down
Loading

0 comments on commit a53706d

Please sign in to comment.