Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Maple sim #4

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 1 addition & 11 deletions simgui-ds.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,6 @@
"visible": false
}
},
"Joysticks": {
"window": {
"visible": false
}
},
"System Joysticks": {
"window": {
"visible": false
}
},
"keyboardJoysticks": [
{
"axisConfig": [
Expand Down Expand Up @@ -104,7 +94,7 @@
],
"robotJoysticks": [
{
"guid": "Keyboard0"
"guid": "030000006d04000015c2000004020000"
}
]
}
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/subsystems/DriveTrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,22 +33,22 @@
@Logged
public class DriveTrain extends SubsystemBase {
// Create SwerveModules
private final SwerveModule m_frontLeft = new SwerveModule(
private final Module m_frontLeft = new Module(
DriveConstants.kFrontLeftDrivingCanId,
DriveConstants.kFrontLeftTurningCanId,
DriveConstants.kFrontLeftChassisAngularOffset);

private final SwerveModule m_frontRight = new SwerveModule(
private final Module m_frontRight = new Module(
DriveConstants.kFrontRightDrivingCanId,
DriveConstants.kFrontRightTurningCanId,
DriveConstants.kFrontRightChassisAngularOffset);

private final SwerveModule m_rearLeft = new SwerveModule(
private final Module m_rearLeft = new Module(
DriveConstants.kRearLeftDrivingCanId,
DriveConstants.kRearLeftTurningCanId,
DriveConstants.kBackLeftChassisAngularOffset);

private final SwerveModule m_rearRight = new SwerveModule(
private final Module m_rearRight = new Module(
DriveConstants.kRearRightDrivingCanId,
DriveConstants.kRearRightTurningCanId,
DriveConstants.kBackRightChassisAngularOffset);
Expand Down Expand Up @@ -86,7 +86,7 @@ public class DriveTrain extends SubsystemBase {
DCMotor.getNeoVortex(1),
DCMotor.getNeo550(1),
Swerve.ModuleConstants.kDrivingMotorReduction,
12.8,
46.42,
Amps.of(60),
Amps.of(20),
Volts.of(0.1),
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/subsystems/GyroIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
package frc.robot.subsystems;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.measure.AngularVelocity;

public interface GyroIO {
Rotation2d getGyroRotation();
AngularVelocity getGyroAngularVelocity();
}
27 changes: 27 additions & 0 deletions src/main/java/frc/robot/subsystems/GyroIONavX.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package frc.robot.subsystems;

import static edu.wpi.first.units.Units.DegreesPerSecond;

import com.studica.frc.AHRS;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.measure.AngularVelocity;

public class GyroIONavX implements GyroIO {

private final AHRS m_gyro = new AHRS(AHRS.NavXComType.kMXP_SPI);
public GyroIONavX() {

}

@Override // specified by GroIOSim interface
public Rotation2d getGyroRotation() {
return m_gyro.getRotation2d();
}

@Override // specified by GroIOSim interface
public AngularVelocity getGyroAngularVelocity() {
return DegreesPerSecond.of(m_gyro.getRate());
}

}
27 changes: 27 additions & 0 deletions src/main/java/frc/robot/subsystems/GyroIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package frc.robot.subsystems;

import static edu.wpi.first.units.Units.RadiansPerSecond;

import org.ironmaple.simulation.drivesims.GyroSimulation;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.AngularVelocityUnit;
import edu.wpi.first.units.measure.AngularVelocity;

public class GyroIOSim implements GyroIO {
private final GyroSimulation gyroSimulation;
public GyroIOSim(GyroSimulation gyroSimulation) {
this.gyroSimulation = gyroSimulation;
}

@Override // specified by GroIOSim interface
public Rotation2d getGyroRotation() {
return this.gyroSimulation.getGyroReading();
}

@Override // specified by GroIOSim interface
public AngularVelocity getGyroAngularVelocity() {
return this.gyroSimulation.getMeasuredAngularVelocity();
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -6,70 +6,14 @@
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.RobotBase;

import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.SparkFlex;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.ControlType;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.sim.SparkAbsoluteEncoderSim;
import com.revrobotics.sim.SparkRelativeEncoderSim;

import frc.robot.configs.Swerve.ModuleConfigs;

@Logged
public class SwerveModule {
private final SparkFlex m_drivingSpark;
private final SparkMax m_turningSpark;
public class Module {

private final RelativeEncoder m_drivingEncoder;
private final AbsoluteEncoder m_turningEncoder;

private final SparkClosedLoopController m_drivingClosedLoopController;
private final SparkClosedLoopController m_turningClosedLoopController;

private double m_chassisAngularOffset = 0;
private SwerveModuleState m_desiredState = new SwerveModuleState(0.0, new Rotation2d());

//sim encoders
public final SparkRelativeEncoderSim m_drivingEncoderSim;
public final SparkAbsoluteEncoderSim m_turningEncoderSim;


/**
* Constructs a SwerveModule and configures the driving and turning motor,
* encoder, and PID controller. This configuration is specific to the REV
* MAXSwerve Module built with NEOs, SPARKS MAX, and a Through Bore
* Encoder.
*/
public SwerveModule(int drivingCANId, int turningCANId, double chassisAngularOffset) {
m_drivingSpark = new SparkFlex(drivingCANId, MotorType.kBrushless);
m_turningSpark = new SparkMax(turningCANId, MotorType.kBrushless);

m_drivingEncoder = m_drivingSpark.getEncoder();
m_turningEncoder = m_turningSpark.getAbsoluteEncoder();

m_drivingClosedLoopController = m_drivingSpark.getClosedLoopController();
m_turningClosedLoopController = m_turningSpark.getClosedLoopController();

// Apply the respective configurations to the SPARKS. Reset parameters before
// applying the configuration to bring the SPARK to a known good state. Persist
// the settings to the SPARK to avoid losing them on a power cycle.
m_drivingSpark.configure(ModuleConfigs.drivingConfig, ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters);
m_turningSpark.configure(ModuleConfigs.turningConfig, ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters);

m_chassisAngularOffset = chassisAngularOffset;

m_drivingEncoderSim = new SparkRelativeEncoderSim(m_drivingSpark);
m_turningEncoderSim = new SparkAbsoluteEncoderSim(m_turningSpark);

m_desiredState.angle = new Rotation2d(m_turningEncoder.getPosition());
}

/**
* Returns the current state of the module.
Expand Down
17 changes: 17 additions & 0 deletions src/main/java/frc/robot/subsystems/ModuleIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
package frc.robot.subsystems;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.LinearVelocity;
import edu.wpi.first.units.measure.Voltage;

public interface ModuleIO {
public void setDriveOutputVoltage(Voltage voltage);
public void setSteerOutputVoltage(Voltage voltage);
public void requestDriveVelocity(LinearVelocity driveVelocitySetpoint);
public void requestSteerPosition(Rotation2d steerFacingSetpoint);
public Rotation2d getSteerFacing();
public Angle getSteerRelativePosition();
public Angle getDriveWheelrPositiond();

}
90 changes: 90 additions & 0 deletions src/main/java/frc/robot/subsystems/ModuleIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
package frc.robot.subsystems;

import org.ironmaple.simulation.drivesims.SwerveModuleSimulation;
import org.ironmaple.simulation.motorsims.ControlRequest;

import static edu.wpi.first.units.Units.*;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.measure.*;


// This is only an example simulation IO implement, please change the code according to your ModuleIO interface
public class ModuleIOSim implements ModuleIO {
private final SwerveModuleSimulation moduleSimulation;
public ModuleIOSim(SwerveModuleSimulation moduleSimulation) {
this.moduleSimulation = moduleSimulation;

// configures the drive motor gains
this.moduleSimulation.getDriveMotorConfigs()
// configures a default feed-forward gains for the drive motor, with 0.1 volts of friction compensation
.withDefaultFeedForward(Volts.of(0.1))
// configures a velocity-voltage close loop controller
.withVelocityVoltageController(
// P gain is 12 volts / 3000 RPM (change it for your code)
// Meaning that: the correction voltage is 12 volts when error is 3000RPM
Volts.per(RPM).ofNative(12.0/3000.0),
// true means the P gain is specified in un-geared motor speed
true
);

// configures the steer motor gains
this.moduleSimulation.getSteerMotorConfigs()
// configures a position-current close loop controller
.withPositionCurrentController(
// P gain is 12 amps / 60 degrees
// Meaning that: the correction current is 20 amps when the steer position error is 60 degrees
Amps.per(Degrees).ofNative(10.0/60.0),
// D gain is zero
Amps.per(DegreesPerSecond).ofNative(0),
// false means the P and D gain are specifed in final mechanism position/velocity
false
);
}

@Override // specified by ModuleIO interface
public void setDriveOutputVoltage(Voltage voltage) {
this.moduleSimulation.requestDriveControl(new ControlRequest.VoltageOut(voltage));
}

@Override // specified by ModuleIO interface
public void setSteerOutputVoltage(Voltage voltage) {
this.moduleSimulation.requestSteerControl(new ControlRequest.VoltageOut(voltage));
}

@Override // specified by ModuleIO interface
public void requestDriveVelocity(LinearVelocity driveVelocitySetpoint) {
// calculates the amount of wheel speed needed to achive the linear speed
final AngularVelocity wheelVelocitySetpoint = RadiansPerSecond.of(
driveVelocitySetpoint.in(MetersPerSecond) / moduleSimulation.WHEEL_RADIUS.in(Meters)
);

// request the drive motor controller to run a closed-loop on velocity
moduleSimulation.requestDriveControl(
new ControlRequest.VelocityVoltage(wheelVelocitySetpoint)
);
}

@Override // specified by ModuleIO interface
public void requestSteerPosition(Rotation2d steerFacingSetpoint) {
// request the steer motor controller to run a close
moduleSimulation.requestSteerControl(
new ControlRequest.PositionCurrent(steerFacingSetpoint.getMeasure())
);
}

@Override // specified by ModuleIO interface
public Rotation2d getSteerFacing() {
return this.moduleSimulation.getSteerAbsoluteFacing();
}

@Override // specified by ModuleIO interface
public Angle getSteerRelativePosition() {
return moduleSimulation.getSteerRelativeEncoderPosition().divide(moduleSimulation.STEER_GEAR_RATIO);
}

@Override // specified by ModuleIO interface
public Angle getDriveWheelrPositiond() {
return moduleSimulation.getDriveWheelFinalPosition();
}
}
Loading
Loading