Skip to content

Commit

Permalink
Simulation fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
bhall-ctre committed Dec 8, 2023
1 parent 5225e1f commit 0383351
Show file tree
Hide file tree
Showing 38 changed files with 66 additions and 66 deletions.
2 changes: 1 addition & 1 deletion cpp/BasicLatencyCompensation/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
2 changes: 1 addition & 1 deletion cpp/CANcoder/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
2 changes: 1 addition & 1 deletion cpp/CommandBasedDrive/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
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::Falcon500(2),
frc::DCMotor::Falcon500FOC(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
2 changes: 1 addition & 1 deletion cpp/CurrentLimits/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
2 changes: 1 addition & 1 deletion cpp/Falcon500ArcadeDrive/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
2 changes: 1 addition & 1 deletion cpp/FusedCANcoder/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
2 changes: 1 addition & 1 deletion cpp/MotionMagic/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
7 changes: 4 additions & 3 deletions cpp/MotionMagic/src/main/cpp/sim/TalonFXSimProfile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
using namespace ctre::phoenix6;

TalonFXSimProfile::TalonFXSimProfile(hardware::TalonFX& falcon, units::kilogram_square_meter_t rotorInertia) :
_motorSim{frc::DCMotor::Falcon500(1), 1, rotorInertia},
_motorSim{frc::DCMotor::Falcon500FOC(1), 1, rotorInertia},
_falcon{falcon} {
}

Expand All @@ -15,9 +15,10 @@ void TalonFXSimProfile::Run() {
_motorSim.Update(GetPeriod());

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

_falcon.GetSimState().SetRawRotorPosition(_motorSim.GetAngularPosition());
_falcon.GetSimState().SetRawRotorPosition(position);
_falcon.GetSimState().SetRotorVelocity(velocity);

_falcon.GetSimState().SetSupplyVoltage(12_V - _falcon.GetSimState().GetSupplyCurrent() * kMotorResistance);
Expand Down
2 changes: 1 addition & 1 deletion cpp/Pigeon2/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
2 changes: 1 addition & 1 deletion cpp/PositionClosedLoop/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
2 changes: 1 addition & 1 deletion cpp/Simulation/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
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::Falcon500(2),
frc::DCMotor::Falcon500FOC(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
2 changes: 1 addition & 1 deletion cpp/VelocityClosedLoop/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
2 changes: 1 addition & 1 deletion cpp/WaitForAll/build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "cpp"
id "google-test-test-suite"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

// Define my targets (RoboRIO) and artifacts (deployable files)
Expand Down
2 changes: 1 addition & 1 deletion java/BasicLatencyCompensation/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

java {
Expand Down
2 changes: 1 addition & 1 deletion java/CANcoder/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

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

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

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.util.Units;
Expand All @@ -19,7 +18,6 @@ class TalonFXSimProfile extends SimProfile {
private final double _gearRatio;

private final DCMotorSim _motorSim;
private final CANcoderSimState _cancoderSim; // We need a sim state in order to change the values of CANcoder

/**
* Creates a new simulation profile for a TalonFX device.
Expand All @@ -38,8 +36,7 @@ public TalonFXSimProfile(final TalonFX falcon, final CANcoder canCoder, final do
this._falcon = falcon;
this._canCoder = canCoder;
this._gearRatio = gearRatio;
this._motorSim = new DCMotorSim(DCMotor.getFalcon500(1), 100, .001);
this._cancoderSim = _canCoder.getSimState();
this._motorSim = new DCMotorSim(DCMotor.getFalcon500Foc(1), gearRatio, .001);
}

/**
Expand All @@ -56,18 +53,15 @@ public void run() {
_motorSim.update(getPeriod());

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

_falcon.getSimState().setRawRotorPosition(position);
_falcon.getSimState().setRotorVelocity(velocity);
_falcon.getSimState().setRawRotorPosition(position_rot);
_falcon.getSimState().setRotorVelocity(velocity_rps);

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

_canCoder.getSimState().setRawPosition(_motorSim.getAngularPositionRotations() / _gearRatio);
_canCoder.getSimState().setVelocity(velocity / _gearRatio);

_cancoderSim.setRawPosition(position);
_cancoderSim.setVelocity(velocity);
_canCoder.getSimState().setRawPosition(position_rot / _gearRatio);
_canCoder.getSimState().setVelocity(velocity_rps / _gearRatio);
}
}
2 changes: 1 addition & 1 deletion java/CommandBasedDrive/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

java {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ public class DriveSubsystem extends SubsystemBase {

/* Simulation model of the drivetrain */
private final DifferentialDrivetrainSim m_driveSim = new DifferentialDrivetrainSim(
DCMotor.getFalcon500(2), // 2 CIMS on each side of the drivetrain.
DCMotor.getFalcon500Foc(2), // 2 CIMS on each side of the drivetrain.
kGearRatio, // Standard AndyMark Gearing reduction.
2.1, // MOI of 2.1 kg m^2 (from CAD model).
26.5, // Mass of the robot is 26.5 kg.
Expand Down
2 changes: 1 addition & 1 deletion java/ControlRequestLimits/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

java {
Expand Down
2 changes: 1 addition & 1 deletion java/CurrentLimits/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

java {
Expand Down
2 changes: 1 addition & 1 deletion java/Falcon500ArcadeDrive/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

java {
Expand Down
2 changes: 1 addition & 1 deletion java/FusedCANcoder/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

java {
Expand Down
4 changes: 2 additions & 2 deletions java/FusedCANcoder/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ public void robotPeriodic() {
}
}

if(m_joystick.getAButton()) {
if (m_joystick.getAButton()) {
/* Clear sticky faults */
m_fx.clearStickyFaults();
}
Expand Down Expand Up @@ -137,7 +137,7 @@ public void testPeriodic() {}

@Override
public void simulationInit() {
PhysicsSim.getInstance().addTalonFX(m_fx, m_cc, 25, 0.001);
PhysicsSim.getInstance().addTalonFX(m_fx, m_cc, 12.8, 0.001);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ public TalonFXSimProfile(final TalonFX falcon, final CANcoder canCoder, final do
this._falcon = falcon;
this._canCoder = canCoder;
this._gearRatio = gearRatio;
this._motorSim = new DCMotorSim(DCMotor.getFalcon500(1), gearRatio, rotorInertia);
this._motorSim = new DCMotorSim(DCMotor.getFalcon500Foc(1), gearRatio, rotorInertia);
}

/**
Expand All @@ -54,15 +54,16 @@ public void run() {
_motorSim.update(getPeriod());

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

_falcon.getSimState().setRawRotorPosition(_motorSim.getAngularPositionRotations());
_falcon.getSimState().setRawRotorPosition(position_rot);
_falcon.getSimState().setRotorVelocity(velocity_rps);

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

_canCoder.getSimState().setRawPosition(_motorSim.getAngularPositionRotations()/_gearRatio);
_canCoder.getSimState().setVelocity(velocity_rps/_gearRatio);
_canCoder.getSimState().setRawPosition(position_rot / _gearRatio);
_canCoder.getSimState().setVelocity(velocity_rps / _gearRatio);

}
}
2 changes: 1 addition & 1 deletion java/MotionMagic/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

java {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class TalonFXSimProfile extends SimProfile {
*/
public TalonFXSimProfile(final TalonFX falcon, final double rotorInertia) {
this._falcon = falcon;
this._motorSim = new DCMotorSim(DCMotor.getFalcon500(1), 1.0, rotorInertia);
this._motorSim = new DCMotorSim(DCMotor.getFalcon500Foc(1), 1.0, rotorInertia);
}

/**
Expand All @@ -49,9 +49,10 @@ public void run() {
_motorSim.update(getPeriod());

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

_falcon.getSimState().setRawRotorPosition(_motorSim.getAngularPositionRotations());
_falcon.getSimState().setRawRotorPosition(position_rot);
_falcon.getSimState().setRotorVelocity(velocity_rps);

_falcon.getSimState().setSupplyVoltage(12 - _falcon.getSimState().getSupplyCurrent() * kMotorResistance);
Expand Down
2 changes: 1 addition & 1 deletion java/Pigeon2/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

java {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class TalonFXSimProfile extends SimProfile {
public TalonFXSimProfile(final TalonFX falcon, final Pigeon2 pigeon, final double rotorInertia) {
this._falcon = falcon;
this._pigeon = pigeon;
this._motorSim = new DCMotorSim(DCMotor.getFalcon500(1), 1.0, rotorInertia);
this._motorSim = new DCMotorSim(DCMotor.getFalcon500Foc(1), 1.0, rotorInertia);
}

/**
Expand All @@ -52,14 +52,15 @@ public void run() {
_motorSim.update(getPeriod());

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

_falcon.getSimState().setRawRotorPosition(_motorSim.getAngularPositionRotations());
_falcon.getSimState().setRawRotorPosition(position_rot);
_falcon.getSimState().setRotorVelocity(velocity_rps);

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

_pigeon.getSimState().setRawYaw(_motorSim.getAngularPositionRotations());
_pigeon.getSimState().setRawYaw(position_rot);

}
}
2 changes: 1 addition & 1 deletion java/PositionClosedLoop/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-1"
id "edu.wpi.first.GradleRIO" version "2024.1.1-beta-3"
}

java {
Expand Down
Loading

0 comments on commit 0383351

Please sign in to comment.