Skip to content

Commit

Permalink
Merge pull request #22 from CrossTheRoadElec/SimAdditions
Browse files Browse the repository at this point in the history
Sim additions
  • Loading branch information
CoryNessCTR authored Dec 8, 2023
2 parents 87c6444 + 41537ba commit 5942179
Show file tree
Hide file tree
Showing 66 changed files with 1,320 additions and 139 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/CurrentLimits/src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ class Robot : public frc::TimedRobot {
void SimulationInit() override;
void SimulationPeriodic() override;

ctre::phoenix6::hardware::TalonFX m_fx{0, "Fred"};
ctre::phoenix6::hardware::TalonFX m_fx{0, "canivore"};
ctre::phoenix6::controls::DutyCycleOut m_output{0};
ctre::phoenix6::configs::CurrentLimitsConfigs m_currentLimits{};

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
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 @@ -30,8 +30,8 @@ class Robot : public frc::TimedRobot {
void SimulationPeriodic() override;


ctre::phoenix6::hardware::TalonFX m_fx{1, "fred"};
ctre::phoenix6::hardware::CANcoder m_cc{1, "fred"};
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();
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
9 changes: 3 additions & 6 deletions cpp/MotionMagic/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,24 +20,21 @@ void Robot::RobotInit() {
configs::TalonFXConfiguration cfg{};

/* Configure current limits */
configs::MotionMagicConfigs mm{};
configs::MotionMagicConfigs &mm = cfg.MotionMagic;
mm.MotionMagicCruiseVelocity = 5; // 5 rotations per second cruise
mm.MotionMagicAcceleration = 10; // Take approximately 0.5 seconds to reach max vel
// Take approximately 0.2 seconds to reach max accel
mm.MotionMagicJerk = 50;
cfg.MotionMagic = mm;

configs::Slot0Configs slot0{};
configs::Slot0Configs &slot0 = cfg.Slot0;
slot0.kP = 60;
slot0.kI = 0;
slot0.kD = 0.1;
slot0.kV = 0.12;
slot0.kS = 0.25; // Approximately 0.25V to get the mechanism moving
cfg.Slot0 = slot0;

configs::FeedbackConfigs fdb{};
configs::FeedbackConfigs &fdb = cfg.Feedback;
fdb.SensorToMechanismRatio = 12.8;
cfg.Feedback = fdb;

ctre::phoenix::StatusCode status = ctre::phoenix::StatusCode::StatusCodeNotInitialized;
for(int i = 0; i < 5; ++i) {
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/MotionMagic/src/main/include/sim/TalonFXSimProfile.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
* Holds information about a simulated TalonFX.
*/
class TalonFXSimProfile : public SimProfile {
units::ohm_t kMotorResistance = 2_mOhm; // Assume 2mOhm resistance for voltage drop calculation
static constexpr units::ohm_t kMotorResistance = 2_mOhm; // Assume 2mOhm resistance for voltage drop calculation
frc::sim::DCMotorSim _motorSim;
ctre::phoenix6::hardware::TalonFX& _falcon;

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
24 changes: 12 additions & 12 deletions java/BasicLatencyCompensation/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,29 +21,29 @@
* project.
*/
public class Robot extends TimedRobot {
private final String CANBUS_NAME = "Fred";
private CANcoder m_cc = new CANcoder(0, CANBUS_NAME);
private TalonFX m_fx = new TalonFX(0, CANBUS_NAME);
private Pigeon2 m_p2 = new Pigeon2(0, CANBUS_NAME);
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 int m_printCount = 0;

private DutyCycleOut m_dutycycle = new DutyCycleOut(0);
private final DutyCycleOut m_dutycycle = new DutyCycleOut(0);

XboxController m_joystick = new XboxController(0);
private final XboxController m_joystick = new XboxController(0);

StatusSignal<Double> m_ccpos = m_cc.getPosition();
StatusSignal<Double> m_fxpos = m_fx.getPosition();
StatusSignal<Double> m_p2yaw = m_p2.getYaw();
StatusSignal<Double> m_ccvel = m_cc.getVelocity();
StatusSignal<Double> m_fxvel = m_fx.getVelocity();
private final StatusSignal<Double> m_ccpos = m_cc.getPosition();
private final StatusSignal<Double> m_fxpos = m_fx.getPosition();
private final StatusSignal<Double> m_p2yaw = m_p2.getYaw();
private final StatusSignal<Double> m_ccvel = m_cc.getVelocity();
private final StatusSignal<Double> m_fxvel = m_fx.getVelocity();
/**
* Pigeon2 can only perform this latency compensation if the Z axis is straight up, since the
* angular velocity Z value comes from the pre-mount orientation gyroscope.
* For more information on what signals have what algorithms applied to them,
* see section 1.6 of the Pigeon 2's User's Guide
* https://store.ctr-electronics.com/content/user-manual/Pigeon2%20User's%20Guide.pdf
*/
StatusSignal<Double> m_p2yawRate = m_p2.getAngularVelocityZ();
private final StatusSignal<Double> m_p2yawRate = m_p2.getAngularVelocityZ();

/**
* This function is run when the robot is first started up and should be used for any
Expand Down
24 changes: 24 additions & 0 deletions java/CANcoder/.Glass/glass.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
{
"NetworkTables": {
"transitory": {
"SmartDashboard": {
"open": true
}
},
"types": {
"/FMSInfo": "FMSInfo",
"/SmartDashboard/mech2d": "Mechanism2d"
},
"windows": {
"/SmartDashboard/mech2d": {
"window": {
"visible": true
}
}
}
},
"NetworkTables Settings": {
"mode": "Client (NT4)",
"serverTeam": "7762"
}
}
12 changes: 9 additions & 3 deletions java/CANcoder/.vscode/launch.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,24 @@
// For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387
"version": "0.2.0",
"configurations": [

{
"type": "java",
"name": "Launch Main",
"request": "launch",
"mainClass": "frc.robot.Main",
"projectName": "CANcoder"
},
{
"type": "wpilib",
"name": "WPILib Desktop Debug",
"request": "launch",
"desktop": true,
"desktop": true
},
{
"type": "wpilib",
"name": "WPILib roboRIO Debug",
"request": "launch",
"desktop": false,
"desktop": false
}
]
}
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
43 changes: 43 additions & 0 deletions java/CANcoder/src/main/java/frc/robot/Mechanisms.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
package frc.robot;

import com.ctre.phoenix6.StatusSignal;

import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.util.Color;
import edu.wpi.first.wpilibj.util.Color8Bit;

/**
* Class to keep all the mechanism-specific objects together and out of the main example
*/
public class Mechanisms {
private final double HEIGHT = 1;
private final double WIDTH = 1;
private final double ROOT_X = WIDTH / 2;
private final double ROOT_Y = HEIGHT / 2;

private Mechanism2d mech = new Mechanism2d(WIDTH, HEIGHT); // Main mechanism object
private MechanismLigament2d wrist = mech.getRoot("base", ROOT_X, ROOT_Y)
.append(new MechanismLigament2d("Wrist", .25, 90, 6, new Color8Bit(Color.kAliceBlue)));

@SuppressWarnings("unused")
private MechanismLigament2d leftArrow = wrist.append(
new MechanismLigament2d("LeftArrow",
0.1,
150,
6,
new Color8Bit(Color.kAliceBlue)));
@SuppressWarnings("unused")
private MechanismLigament2d rightArrow = wrist.append(
new MechanismLigament2d("RightArrow",
0.1,
-150,
6,
new Color8Bit(Color.kAliceBlue)));

public void update(StatusSignal<Double> angle) {
SmartDashboard.putData("mech2d", mech); // Creates a mech2d window in GUI
wrist.setAngle(angle.getValue() * 360); // Converts 1 rotation to 360 degrees
}
}
Loading

0 comments on commit 5942179

Please sign in to comment.