shooterandstuff
This commit is contained in:
@@ -1,6 +1,6 @@
|
||||
plugins {
|
||||
id "java"
|
||||
id "edu.wpi.first.GradleRIO" version "2026.1.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2026.2.1"
|
||||
}
|
||||
|
||||
java {
|
||||
|
||||
38
src/main/deploy/pathplanner/autos/Balles-Grimpe.auto
Normal file
38
src/main/deploy/pathplanner/autos/Balles-Grimpe.auto
Normal file
@@ -0,0 +1,38 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"command": {
|
||||
"type": "sequential",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "Sortir"
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "deadline",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "Aspirer"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "Retour"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
"resetOdom": true,
|
||||
"folder": null,
|
||||
"choreoAuto": false
|
||||
}
|
||||
@@ -1,19 +0,0 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"command": {
|
||||
"type": "sequential",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "SimplePath"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
"resetOdom": true,
|
||||
"folder": null,
|
||||
"choreoAuto": false
|
||||
}
|
||||
File diff suppressed because one or more lines are too long
54
src/main/deploy/pathplanner/paths/Aspirer.path
Normal file
54
src/main/deploy/pathplanner/paths/Aspirer.path
Normal file
@@ -0,0 +1,54 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 7.713431818179517,
|
||||
"y": 6.869375
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 7.71512019907703,
|
||||
"y": 5.599309498510606
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 7.713431818179517,
|
||||
"y": 4.467886363634282
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 7.715861871554869,
|
||||
"y": 5.73629063106375
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
}
|
||||
],
|
||||
"rotationTargets": [],
|
||||
"constraintZones": [],
|
||||
"pointTowardsZones": [],
|
||||
"eventMarkers": [],
|
||||
"globalConstraints": {
|
||||
"maxVelocity": 3.0,
|
||||
"maxAcceleration": 3.0,
|
||||
"maxAngularVelocity": 540.0,
|
||||
"maxAngularAcceleration": 720.0,
|
||||
"nominalVoltage": 12.0,
|
||||
"unlimited": false
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": -90.0
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
"idealStartingState": {
|
||||
"velocity": 0,
|
||||
"rotation": -90.0
|
||||
},
|
||||
"useDefaultConstraints": true
|
||||
}
|
||||
86
src/main/deploy/pathplanner/paths/Retour.path
Normal file
86
src/main/deploy/pathplanner/paths/Retour.path
Normal file
@@ -0,0 +1,86 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 7.785579545453249,
|
||||
"y": 4.540034090910067
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 7.084715909095779,
|
||||
"y": 5.581022727273153
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 4.641999999998702,
|
||||
"y": 7.425943181819158
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 6.920368903788226,
|
||||
"y": 7.435679801066667
|
||||
},
|
||||
"nextControl": {
|
||||
"x": 2.2302045454594164,
|
||||
"y": 7.415636363636789
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 2.3848068181805204,
|
||||
"y": 4.210215909091886
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 2.5394090909139617,
|
||||
"y": 5.4367272727276985
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
}
|
||||
],
|
||||
"rotationTargets": [
|
||||
{
|
||||
"waypointRelativePos": 0.9939540507859759,
|
||||
"rotationDegrees": 180.0
|
||||
}
|
||||
],
|
||||
"constraintZones": [],
|
||||
"pointTowardsZones": [
|
||||
{
|
||||
"fieldPosition": {
|
||||
"x": 4.6,
|
||||
"y": 4.0
|
||||
},
|
||||
"rotationOffset": 0.0,
|
||||
"minWaypointRelativePos": 0.25,
|
||||
"maxWaypointRelativePos": 0.75,
|
||||
"name": "Point Towards Zone"
|
||||
}
|
||||
],
|
||||
"eventMarkers": [],
|
||||
"globalConstraints": {
|
||||
"maxVelocity": 3.0,
|
||||
"maxAcceleration": 3.0,
|
||||
"maxAngularVelocity": 540.0,
|
||||
"maxAngularAcceleration": 720.0,
|
||||
"nominalVoltage": 12.0,
|
||||
"unlimited": false
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": 180.0
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
"idealStartingState": {
|
||||
"velocity": 0,
|
||||
"rotation": -90.0
|
||||
},
|
||||
"useDefaultConstraints": true
|
||||
}
|
||||
@@ -1,75 +0,0 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 4.061722123444247,
|
||||
"y": 5.039
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 4.267799739805012,
|
||||
"y": 4.6820630981604685
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 5.292790014151457,
|
||||
"y": 4.494829275372837
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 4.519661364176327,
|
||||
"y": 4.494829275372837
|
||||
},
|
||||
"nextControl": {
|
||||
"x": 5.980046769810262,
|
||||
"y": 4.494829275372837
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 6.152,
|
||||
"y": 5.296
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 6.066179328079686,
|
||||
"y": 4.809286783590948
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
}
|
||||
],
|
||||
"rotationTargets": [
|
||||
{
|
||||
"waypointRelativePos": 1.0,
|
||||
"rotationDegrees": 90.0
|
||||
}
|
||||
],
|
||||
"constraintZones": [],
|
||||
"pointTowardsZones": [],
|
||||
"eventMarkers": [],
|
||||
"globalConstraints": {
|
||||
"maxVelocity": 3,
|
||||
"maxAcceleration": 3,
|
||||
"maxAngularVelocity": 540,
|
||||
"maxAngularAcceleration": 720,
|
||||
"nominalVoltage": 12.0,
|
||||
"unlimited": false
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": 0.0
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
"idealStartingState": {
|
||||
"velocity": 0,
|
||||
"rotation": 0.0
|
||||
},
|
||||
"useDefaultConstraints": false
|
||||
}
|
||||
66
src/main/deploy/pathplanner/paths/Sortir.path
Normal file
66
src/main/deploy/pathplanner/paths/Sortir.path
Normal file
@@ -0,0 +1,66 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 0.406,
|
||||
"y": 7.663
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 7.043488636363636,
|
||||
"y": 7.570238636363637
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 7.7237386363636364,
|
||||
"y": 6.931215909090908
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 7.500041412044834,
|
||||
"y": 7.042838271689375
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
}
|
||||
],
|
||||
"rotationTargets": [
|
||||
{
|
||||
"waypointRelativePos": 0.28174123337363943,
|
||||
"rotationDegrees": 0.0
|
||||
}
|
||||
],
|
||||
"constraintZones": [],
|
||||
"pointTowardsZones": [],
|
||||
"eventMarkers": [
|
||||
{
|
||||
"name": "Aspirateur",
|
||||
"waypointRelativePos": 0.6550802139037444,
|
||||
"endWaypointRelativePos": 1.0,
|
||||
"command": null
|
||||
}
|
||||
],
|
||||
"globalConstraints": {
|
||||
"maxVelocity": 3.0,
|
||||
"maxAcceleration": 3.0,
|
||||
"maxAngularVelocity": 540.0,
|
||||
"maxAngularAcceleration": 720.0,
|
||||
"nominalVoltage": 12.0,
|
||||
"unlimited": false
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": -90.0
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
"idealStartingState": {
|
||||
"velocity": 0,
|
||||
"rotation": 0.0
|
||||
},
|
||||
"useDefaultConstraints": true
|
||||
}
|
||||
@@ -1,6 +1,6 @@
|
||||
{
|
||||
"robotWidth": 0.762,
|
||||
"robotLength": 0.762,
|
||||
"robotLength": 0.889,
|
||||
"holonomicMode": true,
|
||||
"pathFolders": [],
|
||||
"autoFolders": [],
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
package frc.robot;
|
||||
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
import static edu.wpi.first.units.Units.RPM;
|
||||
import static edu.wpi.first.units.Units.RadiansPerSecond;
|
||||
import static edu.wpi.first.units.Units.RotationsPerSecond;
|
||||
|
||||
@@ -13,91 +14,94 @@ import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
import com.pathplanner.lib.auto.AutoBuilder;
|
||||
import com.pathplanner.lib.commands.FollowPathCommand;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandScheduler;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers;
|
||||
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.subsystems.AprilTagsLimelight;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
import frc.robot.subsystems.Shooter;
|
||||
import frc.robot.utils.Field;
|
||||
|
||||
public class RobotContainer {
|
||||
private double MaxSpeed = 1.0 * TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top
|
||||
// speed
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second
|
||||
// max angular velocity
|
||||
private double MaxSpeed = 1.0 * TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired
|
||||
// top
|
||||
// speed
|
||||
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per
|
||||
// second
|
||||
// max angular velocity
|
||||
|
||||
/* Setting up bindings for necessary control of the swerve drive platform */
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive motors
|
||||
private final SwerveRequest.SwerveDriveBrake brake = new SwerveRequest.SwerveDriveBrake();
|
||||
private final SwerveRequest.PointWheelsAt point = new SwerveRequest.PointWheelsAt();
|
||||
private final SwerveRequest.RobotCentric forwardStraight = new SwerveRequest.RobotCentric()
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
|
||||
/* Setting up bindings for necessary control of the swerve drive platform */
|
||||
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // Use open-loop control for drive
|
||||
// motors
|
||||
|
||||
private final Telemetry logger = new Telemetry(MaxSpeed);
|
||||
private final SwerveRequest.FieldCentricFacingAngle driveWithAngle = new SwerveRequest.FieldCentricFacingAngle()
|
||||
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
|
||||
.withDriveRequestType(DriveRequestType.OpenLoopVoltage)
|
||||
.withHeadingPID(7, 0, 0);
|
||||
|
||||
private final CommandXboxController joystick = new CommandXboxController(0);
|
||||
private final Telemetry logger = new Telemetry(MaxSpeed);
|
||||
|
||||
public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
|
||||
public final AprilTagsLimelight aprilTagsLimelight = new AprilTagsLimelight(drivetrain);
|
||||
private final CommandXboxController joystick = new CommandXboxController(0);
|
||||
|
||||
/* Path follower */
|
||||
private final SendableChooser<Command> autoChooser;
|
||||
private final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
|
||||
private final AprilTagsLimelight aprilTagsLimelight = new AprilTagsLimelight(drivetrain);
|
||||
private final Shooter shooter = new Shooter();
|
||||
|
||||
public RobotContainer() {
|
||||
autoChooser = AutoBuilder.buildAutoChooser("Tests");
|
||||
SmartDashboard.putData("Auto Mode", autoChooser);
|
||||
/* Path follower */
|
||||
private final SendableChooser<Command> autoChooser;
|
||||
|
||||
configureBindings();
|
||||
public RobotContainer() {
|
||||
autoChooser = AutoBuilder.buildAutoChooser("Balles-Grimpe");
|
||||
SmartDashboard.putData("Auto Mode", autoChooser);
|
||||
|
||||
// Warmup PathPlanner to avoid Java pauses
|
||||
CommandScheduler.getInstance().schedule(FollowPathCommand.warmupCommand());
|
||||
}
|
||||
configureBindings();
|
||||
|
||||
private void configureBindings() {
|
||||
// Note that X is defined as forward according to WPILib convention,
|
||||
// and Y is defined as to the left according to WPILib convention.
|
||||
drivetrain.setDefaultCommand(
|
||||
// Drivetrain will execute this command periodically
|
||||
drivetrain.applyRequest(() -> drive.withVelocityX(-joystick.getLeftY() * MaxSpeed)
|
||||
.withVelocityY(-joystick.getLeftX() * MaxSpeed)
|
||||
.withRotationalRate(-joystick.getRightX() * MaxAngularRate)));
|
||||
// Warmup PathPlanner to avoid Java pauses
|
||||
CommandScheduler.getInstance().schedule(FollowPathCommand.warmupCommand());
|
||||
}
|
||||
|
||||
// Idle while the robot is disabled. This ensures the configured
|
||||
// neutral mode is applied to the drive motors while disabled.
|
||||
final var idle = new SwerveRequest.Idle();
|
||||
RobotModeTriggers.disabled().whileTrue(
|
||||
drivetrain.applyRequest(() -> idle).ignoringDisable(true));
|
||||
private void configureBindings() {
|
||||
// Note that X is defined as forward according to WPILib convention,
|
||||
// and Y is defined as to the left according to WPILib convention.
|
||||
drivetrain.setDefaultCommand(
|
||||
// Drivetrain will execute this command periodically
|
||||
drivetrain.applyRequest(() -> drive.withVelocityX(-joystick.getLeftY() * MaxSpeed)
|
||||
.withVelocityY(-joystick.getLeftX() * MaxSpeed)
|
||||
.withRotationalRate((joystick.getLeftTriggerAxis()
|
||||
- joystick.getRightTriggerAxis()) * MaxAngularRate)));
|
||||
|
||||
joystick.a().whileTrue(drivetrain.applyRequest(() -> brake));
|
||||
joystick.b().whileTrue(drivetrain.applyRequest(
|
||||
() -> point.withModuleDirection(new Rotation2d(-joystick.getLeftY(), -joystick.getLeftX()))));
|
||||
joystick.a().whileTrue(drivetrain.applyRequest(() -> {
|
||||
Pose2d pose = drivetrain.getState().Pose;
|
||||
Pose2d hubPose = Field.getHubPose();
|
||||
Pose2d diff = pose.relativeTo(hubPose);
|
||||
return driveWithAngle.withTargetDirection(new Rotation2d(diff.getX(), diff.getY()))
|
||||
.withVelocityX(-joystick.getLeftY() * MaxSpeed)
|
||||
.withVelocityY(-joystick.getLeftX() * MaxSpeed);
|
||||
}));
|
||||
|
||||
joystick.povUp().whileTrue(drivetrain.applyRequest(() -> forwardStraight.withVelocityX(0.5).withVelocityY(0)));
|
||||
joystick.povDown()
|
||||
.whileTrue(drivetrain.applyRequest(() -> forwardStraight.withVelocityX(-0.5).withVelocityY(0)));
|
||||
joystick.x().whileTrue(Commands.runEnd(() -> shooter.set(RPM.of(10000)), () -> shooter.set(RPM.of(0)),
|
||||
shooter));
|
||||
|
||||
// Run SysId routines when holding back/start and X/Y.
|
||||
// Note that each routine should be run exactly once in a single log.
|
||||
joystick.back().and(joystick.y()).whileTrue(drivetrain.sysIdDynamic(Direction.kForward));
|
||||
joystick.back().and(joystick.x()).whileTrue(drivetrain.sysIdDynamic(Direction.kReverse));
|
||||
joystick.start().and(joystick.y()).whileTrue(drivetrain.sysIdQuasistatic(Direction.kForward));
|
||||
joystick.start().and(joystick.x()).whileTrue(drivetrain.sysIdQuasistatic(Direction.kReverse));
|
||||
// Idle while the robot is disabled. This ensures the configured
|
||||
// neutral mode is applied to the drive motors while disabled.
|
||||
final var idle = new SwerveRequest.Idle();
|
||||
RobotModeTriggers.disabled().whileTrue(
|
||||
drivetrain.applyRequest(() -> idle).ignoringDisable(true));
|
||||
|
||||
// Reset the field-centric heading on left bumper press.
|
||||
joystick.leftBumper().onTrue(drivetrain.runOnce(drivetrain::seedFieldCentric));
|
||||
drivetrain.registerTelemetry(logger::telemeterize);
|
||||
}
|
||||
|
||||
drivetrain.registerTelemetry(logger::telemeterize);
|
||||
}
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
/* Run the path selected from the auto chooser */
|
||||
return autoChooser.getSelected();
|
||||
}
|
||||
public Command getAutonomousCommand() {
|
||||
/* Run the path selected from the auto chooser */
|
||||
return autoChooser.getSelected();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,7 +0,0 @@
|
||||
package frc.robot;
|
||||
|
||||
import limelight.Limelight;
|
||||
|
||||
public class Vision {
|
||||
public final Limelight limelight = new Limelight("AprilTags");
|
||||
}
|
||||
@@ -1,19 +1,39 @@
|
||||
package frc.robot.generated;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import static edu.wpi.first.units.Units.Amps;
|
||||
import static edu.wpi.first.units.Units.Inches;
|
||||
import static edu.wpi.first.units.Units.KilogramSquareMeters;
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
import static edu.wpi.first.units.Units.Rotations;
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
|
||||
import com.ctre.phoenix6.CANBus;
|
||||
import com.ctre.phoenix6.configs.*;
|
||||
import com.ctre.phoenix6.hardware.*;
|
||||
import com.ctre.phoenix6.signals.*;
|
||||
import com.ctre.phoenix6.swerve.*;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants.*;
|
||||
import com.ctre.phoenix6.configs.CANcoderConfiguration;
|
||||
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
|
||||
import com.ctre.phoenix6.configs.Pigeon2Configuration;
|
||||
import com.ctre.phoenix6.configs.Slot0Configs;
|
||||
import com.ctre.phoenix6.configs.TalonFXConfiguration;
|
||||
import com.ctre.phoenix6.hardware.CANcoder;
|
||||
import com.ctre.phoenix6.hardware.TalonFX;
|
||||
import com.ctre.phoenix6.signals.StaticFeedforwardSignValue;
|
||||
import com.ctre.phoenix6.swerve.SwerveDrivetrain;
|
||||
import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants.DriveMotorArrangement;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants.SteerFeedbackType;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants.SteerMotorArrangement;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstantsFactory;
|
||||
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N3;
|
||||
import edu.wpi.first.units.measure.*;
|
||||
|
||||
import edu.wpi.first.units.measure.Angle;
|
||||
import edu.wpi.first.units.measure.Current;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.units.measure.LinearVelocity;
|
||||
import edu.wpi.first.units.measure.MomentOfInertia;
|
||||
import edu.wpi.first.units.measure.Voltage;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
|
||||
// Generated by the 2026 Tuner X Swerve Project Generator
|
||||
@@ -21,17 +41,18 @@ import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
public class TunerConstants {
|
||||
// Both sets of gains need to be tuned to your individual robot.
|
||||
|
||||
// The steer motor uses any SwerveModule.SteerRequestType control request with the
|
||||
// The steer motor uses any SwerveModule.SteerRequestType control request with
|
||||
// the
|
||||
// output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput
|
||||
private static final Slot0Configs steerGains = new Slot0Configs()
|
||||
.withKP(100).withKI(0).withKD(0.5)
|
||||
.withKS(0.1).withKV(1.91).withKA(0)
|
||||
.withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign);
|
||||
.withKP(100).withKI(0).withKD(0.5)
|
||||
.withKS(0.1).withKV(1.91).withKA(0)
|
||||
.withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign);
|
||||
// When using closed-loop control, the drive motor uses the control
|
||||
// output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput
|
||||
private static final Slot0Configs driveGains = new Slot0Configs()
|
||||
.withKP(0.1).withKI(0).withKD(0)
|
||||
.withKS(0).withKV(0.124);
|
||||
.withKP(0.1).withKI(0).withKD(0)
|
||||
.withKS(0).withKV(0.124);
|
||||
|
||||
// The closed-loop output type to use for the steer motors;
|
||||
// This affects the PID/FF gains for the steer motors
|
||||
@@ -53,17 +74,25 @@ public class TunerConstants {
|
||||
// This needs to be tuned to your individual robot
|
||||
private static final Current kSlipCurrent = Amps.of(120);
|
||||
|
||||
// Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null.
|
||||
// Some configs will be overwritten; check the `with*InitialConfigs()` API documentation.
|
||||
private static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration();
|
||||
// Initial configs for the drive and steer motors and the azimuth encoder; these
|
||||
// cannot be null.
|
||||
// Some configs will be overwritten; check the `with*InitialConfigs()` API
|
||||
// documentation.
|
||||
private static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration()
|
||||
.withCurrentLimits(
|
||||
new CurrentLimitsConfigs()
|
||||
.withStatorCurrentLimit(kSlipCurrent)
|
||||
.withStatorCurrentLimitEnable(true)
|
||||
.withSupplyCurrentLimit(Amps.of(70))
|
||||
.withSupplyCurrentLimitEnable(true));
|
||||
private static final TalonFXConfiguration steerInitialConfigs = new TalonFXConfiguration()
|
||||
.withCurrentLimits(
|
||||
new CurrentLimitsConfigs()
|
||||
// Swerve azimuth does not require much torque output, so we can set a relatively low
|
||||
// stator current limit to help avoid brownouts without impacting performance.
|
||||
.withStatorCurrentLimit(Amps.of(60))
|
||||
.withStatorCurrentLimitEnable(true)
|
||||
);
|
||||
.withCurrentLimits(
|
||||
new CurrentLimitsConfigs()
|
||||
// Swerve azimuth does not require much torque output, so we can set a
|
||||
// relatively low
|
||||
// stator current limit to help avoid brownouts without impacting performance.
|
||||
.withStatorCurrentLimit(Amps.of(60))
|
||||
.withStatorCurrentLimitEnable(true));
|
||||
private static final CANcoderConfiguration encoderInitialConfigs = new CANcoderConfiguration();
|
||||
// Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs
|
||||
private static final Pigeon2Configuration pigeonConfigs = null;
|
||||
@@ -101,8 +130,7 @@ public class TunerConstants {
|
||||
.withPigeon2Id(kPigeonId)
|
||||
.withPigeon2Configs(pigeonConfigs);
|
||||
|
||||
private static final SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> ConstantCreator =
|
||||
new SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>()
|
||||
private static final SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> ConstantCreator = new SwerveModuleConstantsFactory<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>()
|
||||
.withDriveMotorGearRatio(kDriveGearRatio)
|
||||
.withSteerMotorGearRatio(kSteerGearRatio)
|
||||
.withCouplingGearRatio(kCoupleRatio)
|
||||
@@ -124,7 +152,6 @@ public class TunerConstants {
|
||||
.withSteerFrictionVoltage(kSteerFrictionVoltage)
|
||||
.withDriveFrictionVoltage(kDriveFrictionVoltage);
|
||||
|
||||
|
||||
// Front Left
|
||||
private static final int kFrontLeftDriveMotorId = 3;
|
||||
private static final int kFrontLeftSteerMotorId = 2;
|
||||
@@ -169,27 +196,26 @@ public class TunerConstants {
|
||||
private static final Distance kBackRightXPos = Inches.of(-10);
|
||||
private static final Distance kBackRightYPos = Inches.of(-10);
|
||||
|
||||
|
||||
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontLeft =
|
||||
ConstantCreator.createModuleConstants(
|
||||
kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset,
|
||||
kFrontLeftXPos, kFrontLeftYPos, kInvertLeftSide, kFrontLeftSteerMotorInverted, kFrontLeftEncoderInverted
|
||||
);
|
||||
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontRight =
|
||||
ConstantCreator.createModuleConstants(
|
||||
kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset,
|
||||
kFrontRightXPos, kFrontRightYPos, kInvertRightSide, kFrontRightSteerMotorInverted, kFrontRightEncoderInverted
|
||||
);
|
||||
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackLeft =
|
||||
ConstantCreator.createModuleConstants(
|
||||
kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset,
|
||||
kBackLeftXPos, kBackLeftYPos, kInvertLeftSide, kBackLeftSteerMotorInverted, kBackLeftEncoderInverted
|
||||
);
|
||||
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackRight =
|
||||
ConstantCreator.createModuleConstants(
|
||||
kBackRightSteerMotorId, kBackRightDriveMotorId, kBackRightEncoderId, kBackRightEncoderOffset,
|
||||
kBackRightXPos, kBackRightYPos, kInvertRightSide, kBackRightSteerMotorInverted, kBackRightEncoderInverted
|
||||
);
|
||||
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontLeft = ConstantCreator
|
||||
.createModuleConstants(
|
||||
kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset,
|
||||
kFrontLeftXPos, kFrontLeftYPos, kInvertLeftSide, kFrontLeftSteerMotorInverted,
|
||||
kFrontLeftEncoderInverted);
|
||||
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> FrontRight = ConstantCreator
|
||||
.createModuleConstants(
|
||||
kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset,
|
||||
kFrontRightXPos, kFrontRightYPos, kInvertRightSide, kFrontRightSteerMotorInverted,
|
||||
kFrontRightEncoderInverted);
|
||||
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackLeft = ConstantCreator
|
||||
.createModuleConstants(
|
||||
kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset,
|
||||
kBackLeftXPos, kBackLeftYPos, kInvertLeftSide, kBackLeftSteerMotorInverted,
|
||||
kBackLeftEncoderInverted);
|
||||
public static final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> BackRight = ConstantCreator
|
||||
.createModuleConstants(
|
||||
kBackRightSteerMotorId, kBackRightDriveMotorId, kBackRightEncoderId, kBackRightEncoderOffset,
|
||||
kBackRightXPos, kBackRightYPos, kInvertRightSide, kBackRightSteerMotorInverted,
|
||||
kBackRightEncoderInverted);
|
||||
|
||||
/**
|
||||
* Creates a CommandSwerveDrivetrain instance.
|
||||
@@ -197,40 +223,41 @@ public class TunerConstants {
|
||||
*/
|
||||
public static CommandSwerveDrivetrain createDrivetrain() {
|
||||
return new CommandSwerveDrivetrain(
|
||||
DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight
|
||||
);
|
||||
DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Swerve Drive class utilizing CTR Electronics' Phoenix 6 API with the selected device types.
|
||||
* Swerve Drive class utilizing CTR Electronics' Phoenix 6 API with the selected
|
||||
* device types.
|
||||
*/
|
||||
public static class TunerSwerveDrivetrain extends SwerveDrivetrain<TalonFX, TalonFX, CANcoder> {
|
||||
/**
|
||||
* Constructs a CTRE SwerveDrivetrain using the specified constants.
|
||||
* <p>
|
||||
* This constructs the underlying hardware devices, so users should not construct
|
||||
* the devices themselves. If they need the devices, they can access them through
|
||||
* This constructs the underlying hardware devices, so users should not
|
||||
* construct
|
||||
* the devices themselves. If they need the devices, they can access them
|
||||
* through
|
||||
* getters in the classes.
|
||||
*
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve drive
|
||||
* @param modules Constants for each specific module
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve drive
|
||||
* @param modules Constants for each specific module
|
||||
*/
|
||||
public TunerSwerveDrivetrain(
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
SwerveModuleConstants<?, ?, ?>... modules
|
||||
) {
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
SwerveModuleConstants<?, ?, ?>... modules) {
|
||||
super(
|
||||
TalonFX::new, TalonFX::new, CANcoder::new,
|
||||
drivetrainConstants, modules
|
||||
);
|
||||
TalonFX::new, TalonFX::new, CANcoder::new,
|
||||
drivetrainConstants, modules);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructs a CTRE SwerveDrivetrain using the specified constants.
|
||||
* <p>
|
||||
* This constructs the underlying hardware devices, so users should not construct
|
||||
* the devices themselves. If they need the devices, they can access them through
|
||||
* This constructs the underlying hardware devices, so users should not
|
||||
* construct
|
||||
* the devices themselves. If they need the devices, they can access them
|
||||
* through
|
||||
* getters in the classes.
|
||||
*
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve drive
|
||||
@@ -240,47 +267,51 @@ public class TunerConstants {
|
||||
* @param modules Constants for each specific module
|
||||
*/
|
||||
public TunerSwerveDrivetrain(
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
double odometryUpdateFrequency,
|
||||
SwerveModuleConstants<?, ?, ?>... modules
|
||||
) {
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
double odometryUpdateFrequency,
|
||||
SwerveModuleConstants<?, ?, ?>... modules) {
|
||||
super(
|
||||
TalonFX::new, TalonFX::new, CANcoder::new,
|
||||
drivetrainConstants, odometryUpdateFrequency, modules
|
||||
);
|
||||
TalonFX::new, TalonFX::new, CANcoder::new,
|
||||
drivetrainConstants, odometryUpdateFrequency, modules);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructs a CTRE SwerveDrivetrain using the specified constants.
|
||||
* <p>
|
||||
* This constructs the underlying hardware devices, so users should not construct
|
||||
* the devices themselves. If they need the devices, they can access them through
|
||||
* This constructs the underlying hardware devices, so users should not
|
||||
* construct
|
||||
* the devices themselves. If they need the devices, they can access them
|
||||
* through
|
||||
* getters in the classes.
|
||||
*
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve drive
|
||||
* @param drivetrainConstants Drivetrain-wide constants for the swerve
|
||||
* drive
|
||||
* @param odometryUpdateFrequency The frequency to run the odometry loop. If
|
||||
* unspecified or set to 0 Hz, this is 250 Hz on
|
||||
* unspecified or set to 0 Hz, this is 250 Hz
|
||||
* on
|
||||
* CAN FD, and 100 Hz on CAN 2.0.
|
||||
* @param odometryStandardDeviation The standard deviation for odometry calculation
|
||||
* in the form [x, y, theta]ᵀ, with units in meters
|
||||
* @param odometryStandardDeviation The standard deviation for odometry
|
||||
* calculation
|
||||
* in the form [x, y, theta]ᵀ, with units in
|
||||
* meters
|
||||
* and radians
|
||||
* @param visionStandardDeviation The standard deviation for vision calculation
|
||||
* in the form [x, y, theta]ᵀ, with units in meters
|
||||
* @param visionStandardDeviation The standard deviation for vision
|
||||
* calculation
|
||||
* in the form [x, y, theta]ᵀ, with units in
|
||||
* meters
|
||||
* and radians
|
||||
* @param modules Constants for each specific module
|
||||
*/
|
||||
public TunerSwerveDrivetrain(
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
double odometryUpdateFrequency,
|
||||
Matrix<N3, N1> odometryStandardDeviation,
|
||||
Matrix<N3, N1> visionStandardDeviation,
|
||||
SwerveModuleConstants<?, ?, ?>... modules
|
||||
) {
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
double odometryUpdateFrequency,
|
||||
Matrix<N3, N1> odometryStandardDeviation,
|
||||
Matrix<N3, N1> visionStandardDeviation,
|
||||
SwerveModuleConstants<?, ?, ?>... modules) {
|
||||
super(
|
||||
TalonFX::new, TalonFX::new, CANcoder::new,
|
||||
drivetrainConstants, odometryUpdateFrequency,
|
||||
odometryStandardDeviation, visionStandardDeviation, modules
|
||||
);
|
||||
TalonFX::new, TalonFX::new, CANcoder::new,
|
||||
drivetrainConstants, odometryUpdateFrequency,
|
||||
odometryStandardDeviation, visionStandardDeviation, modules);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -12,7 +12,7 @@ public class AprilTagsLimelight extends SubsystemBase {
|
||||
|
||||
private CommandSwerveDrivetrain drivetrain;
|
||||
private final Limelight limelight = new Limelight("AprilTags");
|
||||
private final LimelightPoseEstimator poseEstimator = limelight.createPoseEstimator(EstimationMode.MEGATAG2);;
|
||||
private final LimelightPoseEstimator poseEstimator = limelight.createPoseEstimator(EstimationMode.MEGATAG2);
|
||||
|
||||
public AprilTagsLimelight(CommandSwerveDrivetrain drivetrain) {
|
||||
this.drivetrain = drivetrain;
|
||||
|
||||
@@ -1,6 +1,9 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import static edu.wpi.first.units.Units.Inches;
|
||||
import static edu.wpi.first.units.Units.Pounds;
|
||||
import static edu.wpi.first.units.Units.Second;
|
||||
import static edu.wpi.first.units.Units.Seconds;
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
|
||||
import java.util.Optional;
|
||||
@@ -16,20 +19,25 @@ import com.pathplanner.lib.config.PIDConstants;
|
||||
import com.pathplanner.lib.config.RobotConfig;
|
||||
import com.pathplanner.lib.controllers.PPHolonomicDriveController;
|
||||
|
||||
import dev.doglog.DogLog;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.math.numbers.N3;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
import edu.wpi.first.wpilibj.Notifier;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
|
||||
import frc.robot.generated.TunerConstants;
|
||||
import frc.robot.generated.TunerConstants.TunerSwerveDrivetrain;
|
||||
import frc.robot.utils.simulation.MapleSimSwerveDrivetrain;
|
||||
import limelight.networktables.Orientation3d;
|
||||
|
||||
/**
|
||||
@@ -42,7 +50,6 @@ import limelight.networktables.Orientation3d;
|
||||
public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Subsystem {
|
||||
private static final double kSimLoopPeriod = 0.004; // 4 ms
|
||||
private Notifier m_simNotifier = null;
|
||||
private double m_lastSimTime;
|
||||
|
||||
/* Blue alliance sees forward as 0 degrees (toward red alliance wall) */
|
||||
private static final Rotation2d kBlueAlliancePerspectiveRotation = Rotation2d.kZero;
|
||||
@@ -137,7 +144,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
public CommandSwerveDrivetrain(
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
SwerveModuleConstants<?, ?, ?>... modules) {
|
||||
super(drivetrainConstants, modules);
|
||||
super(drivetrainConstants, MapleSimSwerveDrivetrain.regulateModuleConstantsForSimulation(modules));
|
||||
if (Utils.isSimulation()) {
|
||||
startSimThread();
|
||||
}
|
||||
@@ -163,7 +170,8 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
SwerveDrivetrainConstants drivetrainConstants,
|
||||
double odometryUpdateFrequency,
|
||||
SwerveModuleConstants<?, ?, ?>... modules) {
|
||||
super(drivetrainConstants, odometryUpdateFrequency, modules);
|
||||
super(drivetrainConstants, odometryUpdateFrequency,
|
||||
MapleSimSwerveDrivetrain.regulateModuleConstantsForSimulation(modules));
|
||||
if (Utils.isSimulation()) {
|
||||
startSimThread();
|
||||
}
|
||||
@@ -204,7 +212,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
Matrix<N3, N1> visionStandardDeviation,
|
||||
SwerveModuleConstants<?, ?, ?>... modules) {
|
||||
super(drivetrainConstants, odometryUpdateFrequency, odometryStandardDeviation, visionStandardDeviation,
|
||||
modules);
|
||||
MapleSimSwerveDrivetrain.regulateModuleConstantsForSimulation(modules));
|
||||
if (Utils.isSimulation()) {
|
||||
startSimThread();
|
||||
}
|
||||
@@ -302,20 +310,36 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
m_hasAppliedOperatorPerspective = true;
|
||||
});
|
||||
}
|
||||
|
||||
DogLog.log("BatteryVoltage", RobotController.getBatteryVoltage());
|
||||
DogLog.log("Drive/OdometryPose", getState().Pose);
|
||||
DogLog.log("Drive/TargetStates", getState().ModuleTargets);
|
||||
DogLog.log("Drive/MeasuredStates", getState().ModuleStates);
|
||||
DogLog.log("Drive/MeasuredSpeeds", getState().Speeds);
|
||||
if (mapleSimSwerveDrivetrain != null)
|
||||
DogLog.log("Drive/SimulationPose", mapleSimSwerveDrivetrain.mapleSimDrive.getSimulatedDriveTrainPose());
|
||||
}
|
||||
|
||||
private MapleSimSwerveDrivetrain mapleSimSwerveDrivetrain = null;
|
||||
|
||||
private void startSimThread() {
|
||||
m_lastSimTime = Utils.getCurrentTimeSeconds();
|
||||
|
||||
mapleSimSwerveDrivetrain = new MapleSimSwerveDrivetrain(
|
||||
Seconds.of(kSimLoopPeriod),
|
||||
Pounds.of(115), // robot weight
|
||||
Inches.of(35), // bumper length
|
||||
Inches.of(30), // bumper width
|
||||
DCMotor.getKrakenX60(1), // drive motor type
|
||||
DCMotor.getKrakenX60(1), // steer motor type
|
||||
1.2, // wheel COF
|
||||
getModuleLocations(),
|
||||
getPigeon2(),
|
||||
getModules(),
|
||||
TunerConstants.FrontLeft,
|
||||
TunerConstants.FrontRight,
|
||||
TunerConstants.BackLeft,
|
||||
TunerConstants.BackRight);
|
||||
/* Run simulation at a faster rate so PID gains behave more reasonably */
|
||||
m_simNotifier = new Notifier(() -> {
|
||||
final double currentTime = Utils.getCurrentTimeSeconds();
|
||||
double deltaTime = currentTime - m_lastSimTime;
|
||||
m_lastSimTime = currentTime;
|
||||
|
||||
/* use the measured time delta, get battery voltage from WPILib */
|
||||
updateSimState(deltaTime, RobotController.getBatteryVoltage());
|
||||
});
|
||||
m_simNotifier = new Notifier(mapleSimSwerveDrivetrain::update);
|
||||
m_simNotifier.startPeriodic(kSimLoopPeriod);
|
||||
}
|
||||
|
||||
@@ -372,4 +396,12 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
|
||||
public Optional<Pose2d> samplePoseAt(double timestampSeconds) {
|
||||
return super.samplePoseAt(Utils.fpgaToCurrentTime(timestampSeconds));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void resetPose(Pose2d pose) {
|
||||
if (this.mapleSimSwerveDrivetrain != null)
|
||||
mapleSimSwerveDrivetrain.mapleSimDrive.setSimulationWorldPose(pose);
|
||||
Timer.delay(0.05); // Wait for simulation to update
|
||||
super.resetPose(pose);
|
||||
}
|
||||
}
|
||||
|
||||
64
src/main/java/frc/robot/subsystems/Shooter.java
Normal file
64
src/main/java/frc/robot/subsystems/Shooter.java
Normal file
@@ -0,0 +1,64 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import static edu.wpi.first.units.Units.RPM;
|
||||
|
||||
import com.revrobotics.PersistMode;
|
||||
import com.revrobotics.ResetMode;
|
||||
import com.revrobotics.sim.SparkFlexSim;
|
||||
import com.revrobotics.spark.SparkBase.ControlType;
|
||||
import com.revrobotics.spark.SparkFlex;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
|
||||
|
||||
import dev.doglog.DogLog;
|
||||
|
||||
import com.revrobotics.spark.config.SparkFlexConfig;
|
||||
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.units.measure.AngularVelocity;
|
||||
import edu.wpi.first.wpilibj.simulation.BatterySim;
|
||||
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
|
||||
import edu.wpi.first.wpilibj.simulation.RoboRioSim;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Shooter extends SubsystemBase {
|
||||
|
||||
private DCMotor motor = DCMotor.getNeoVortex(1);
|
||||
|
||||
private FlywheelSim flywheelSim = new FlywheelSim(
|
||||
LinearSystemId.createFlywheelSystem(motor, 0.001, 0.5), motor);
|
||||
|
||||
private SparkFlex flex = new SparkFlex(1, MotorType.kBrushless);
|
||||
private SparkFlexSim flexSim = new SparkFlexSim(flex, motor);
|
||||
|
||||
public Shooter() {
|
||||
SparkFlexConfig flexConfig = new SparkFlexConfig();
|
||||
flexConfig.smartCurrentLimit(40).idleMode(IdleMode.kCoast);
|
||||
flexConfig.closedLoop.p(0.27).feedForward.kV(0.11).kA(0);
|
||||
|
||||
flex.configure(flexConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
|
||||
}
|
||||
|
||||
public void set(AngularVelocity vel) {
|
||||
flex.getClosedLoopController().setSetpoint(vel.in(RPM), ControlType.kVelocity);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
DogLog.log("Shooter/Flex", flex.get());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void simulationPeriodic() {
|
||||
flywheelSim.setInput(flexSim.getAppliedOutput() * RoboRioSim.getVInVoltage());
|
||||
flywheelSim.update(0.02);
|
||||
|
||||
flexSim.iterate(
|
||||
flywheelSim.getAngularVelocityRPM(), RoboRioSim.getVInVoltage(), 0.02);
|
||||
|
||||
RoboRioSim.setVInVoltage(BatterySim.calculateDefaultBatteryLoadedVoltage(flywheelSim.getCurrentDrawAmps()));
|
||||
|
||||
DogLog.log("Shooter/FlexSim", flexSim.getVelocity());
|
||||
}
|
||||
}
|
||||
24
src/main/java/frc/robot/utils/Field.java
Normal file
24
src/main/java/frc/robot/utils/Field.java
Normal file
@@ -0,0 +1,24 @@
|
||||
package frc.robot.utils;
|
||||
|
||||
import static edu.wpi.first.units.Units.Meters;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||
|
||||
public class Field {
|
||||
public static Pose2d getHubPose() {
|
||||
Optional<Alliance> alliance = DriverStation.getAlliance();
|
||||
if (alliance.isEmpty()) {
|
||||
return new Pose2d();
|
||||
} else if (alliance.get() == Alliance.Blue) {
|
||||
return new Pose2d(Meters.of(4.6), Meters.of(4.03), new Rotation2d());
|
||||
} else {
|
||||
return new Pose2d(Meters.of(16.5-4.6), Meters.of(4.03), new Rotation2d());
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,296 @@
|
||||
package frc.robot.utils.simulation;
|
||||
|
||||
// Copyright 2021-2025 Iron Maple 5516
|
||||
// Original Source:
|
||||
// https://github.com/Shenzhen-Robotics-Alliance/maple-sim/blob/main/templates/CTRE%20Swerve%20with%20maple-sim/src/main/java/frc/robot/utils/simulation/MapleSimSwerveDrivetrain.java
|
||||
//
|
||||
// This code is licensed under MIT license (see https://mit-license.org/)
|
||||
import static edu.wpi.first.units.Units.KilogramSquareMeters;
|
||||
import static edu.wpi.first.units.Units.Meters;
|
||||
import static edu.wpi.first.units.Units.RadiansPerSecond;
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
|
||||
import org.ironmaple.simulation.SimulatedArena;
|
||||
import org.ironmaple.simulation.drivesims.COTS;
|
||||
import org.ironmaple.simulation.drivesims.SwerveDriveSimulation;
|
||||
import org.ironmaple.simulation.drivesims.SwerveModuleSimulation;
|
||||
import org.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig;
|
||||
import org.ironmaple.simulation.drivesims.configs.SwerveModuleSimulationConfig;
|
||||
import org.ironmaple.simulation.motorsims.SimulatedBattery;
|
||||
import org.ironmaple.simulation.motorsims.SimulatedMotorController;
|
||||
|
||||
import com.ctre.phoenix6.configs.CANcoderConfiguration;
|
||||
import com.ctre.phoenix6.configs.Slot0Configs;
|
||||
import com.ctre.phoenix6.configs.TalonFXConfiguration;
|
||||
import com.ctre.phoenix6.hardware.CANcoder;
|
||||
import com.ctre.phoenix6.hardware.Pigeon2;
|
||||
import com.ctre.phoenix6.hardware.TalonFX;
|
||||
import com.ctre.phoenix6.signals.StaticFeedforwardSignValue;
|
||||
import com.ctre.phoenix6.sim.CANcoderSimState;
|
||||
import com.ctre.phoenix6.sim.Pigeon2SimState;
|
||||
import com.ctre.phoenix6.sim.TalonFXSimState;
|
||||
import com.ctre.phoenix6.swerve.SwerveDrivetrain;
|
||||
import com.ctre.phoenix6.swerve.SwerveModule;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.units.measure.Angle;
|
||||
import edu.wpi.first.units.measure.AngularVelocity;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.units.measure.Mass;
|
||||
import edu.wpi.first.units.measure.Time;
|
||||
import edu.wpi.first.units.measure.Voltage;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
*
|
||||
*
|
||||
* <h2>Injects Maple-Sim simulation data into a CTRE swerve drivetrain.</h2>
|
||||
*
|
||||
* <p>
|
||||
* This class retrieves simulation data from Maple-Sim and injects it into the
|
||||
* CTRE
|
||||
* {@link com.ctre.phoenix6.swerve.SwerveDrivetrain} instance.
|
||||
*
|
||||
* <p>
|
||||
* It replaces the {@link com.ctre.phoenix6.swerve.SimSwerveDrivetrain} class.
|
||||
*/
|
||||
public class MapleSimSwerveDrivetrain {
|
||||
private final Pigeon2SimState pigeonSim;
|
||||
private final SimSwerveModule[] simModules;
|
||||
public final SwerveDriveSimulation mapleSimDrive;
|
||||
|
||||
/**
|
||||
*
|
||||
*
|
||||
* <h2>Constructs a drivetrain simulation using the specified parameters.</h2>
|
||||
*
|
||||
* @param simPeriod the time period of the simulation
|
||||
* @param robotMassWithBumpers the total mass of the robot, including bumpers
|
||||
* @param bumperLengthX the length of the bumper along the X-axis
|
||||
* (influences the collision space of the robot)
|
||||
* @param bumperWidthY the width of the bumper along the Y-axis
|
||||
* (influences the collision space of the robot)
|
||||
* @param driveMotorModel the {@link DCMotor} model for the drive motor,
|
||||
* typically <code>DCMotor.getKrakenX60Foc()
|
||||
* </code>
|
||||
* @param steerMotorModel the {@link DCMotor} model for the steer motor,
|
||||
* typically <code>DCMotor.getKrakenX60Foc()
|
||||
* </code>
|
||||
* @param wheelCOF the coefficient of friction of the drive wheels
|
||||
* @param moduleLocations the locations of the swerve modules on the robot,
|
||||
* in the order <code>FL, FR, BL, BR</code>
|
||||
* @param pigeon the {@link Pigeon2} IMU used in the drivetrain
|
||||
* @param modules the {@link SwerveModule}s, typically obtained via
|
||||
* {@link SwerveDrivetrain#getModules()}
|
||||
* @param moduleConstants the constants for the swerve modules
|
||||
*/
|
||||
@SafeVarargs
|
||||
public MapleSimSwerveDrivetrain(
|
||||
Time simPeriod,
|
||||
Mass robotMassWithBumpers,
|
||||
Distance bumperLengthX,
|
||||
Distance bumperWidthY,
|
||||
DCMotor driveMotorModel,
|
||||
DCMotor steerMotorModel,
|
||||
double wheelCOF,
|
||||
Translation2d[] moduleLocations,
|
||||
Pigeon2 pigeon,
|
||||
SwerveModule<TalonFX, TalonFX, CANcoder>[] modules,
|
||||
SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>... moduleConstants) {
|
||||
this.pigeonSim = pigeon.getSimState();
|
||||
simModules = new SimSwerveModule[moduleConstants.length];
|
||||
DriveTrainSimulationConfig simulationConfig = DriveTrainSimulationConfig.Default()
|
||||
.withRobotMass(robotMassWithBumpers)
|
||||
.withBumperSize(bumperLengthX, bumperWidthY)
|
||||
.withGyro(COTS.ofPigeon2())
|
||||
.withCustomModuleTranslations(moduleLocations)
|
||||
.withSwerveModule(new SwerveModuleSimulationConfig(
|
||||
driveMotorModel,
|
||||
steerMotorModel,
|
||||
moduleConstants[0].DriveMotorGearRatio,
|
||||
moduleConstants[0].SteerMotorGearRatio,
|
||||
Volts.of(moduleConstants[0].DriveFrictionVoltage),
|
||||
Volts.of(moduleConstants[0].SteerFrictionVoltage),
|
||||
Meters.of(moduleConstants[0].WheelRadius),
|
||||
KilogramSquareMeters.of(moduleConstants[0].SteerInertia),
|
||||
wheelCOF));
|
||||
mapleSimDrive = new SwerveDriveSimulation(simulationConfig, new Pose2d());
|
||||
|
||||
SwerveModuleSimulation[] moduleSimulations = mapleSimDrive.getModules();
|
||||
for (int i = 0; i < this.simModules.length; i++)
|
||||
simModules[i] = new SimSwerveModule(moduleConstants[0], moduleSimulations[i], modules[i]);
|
||||
|
||||
SimulatedArena.overrideSimulationTimings(simPeriod, 1);
|
||||
SimulatedArena.getInstance().addDriveTrainSimulation(mapleSimDrive);
|
||||
}
|
||||
|
||||
/**
|
||||
*
|
||||
*
|
||||
* <h2>Update the simulation.</h2>
|
||||
*
|
||||
* <p>
|
||||
* Updates the Maple-Sim simulation and injects the results into the simulated
|
||||
* CTRE devices, including motors and
|
||||
* the IMU.
|
||||
*/
|
||||
public void update() {
|
||||
SimulatedArena.getInstance().simulationPeriodic();
|
||||
pigeonSim.setRawYaw(
|
||||
mapleSimDrive.getSimulatedDriveTrainPose().getRotation().getMeasure());
|
||||
pigeonSim.setAngularVelocityZ(RadiansPerSecond.of(
|
||||
mapleSimDrive.getDriveTrainSimulatedChassisSpeedsRobotRelative().omegaRadiansPerSecond));
|
||||
}
|
||||
|
||||
/**
|
||||
*
|
||||
*
|
||||
* <h1>Represents the simulation of a single {@link SwerveModule}.</h1>
|
||||
*/
|
||||
protected static class SimSwerveModule {
|
||||
public final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> moduleConstant;
|
||||
public final SwerveModuleSimulation moduleSimulation;
|
||||
|
||||
public SimSwerveModule(
|
||||
SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> moduleConstant,
|
||||
SwerveModuleSimulation moduleSimulation,
|
||||
SwerveModule<TalonFX, TalonFX, CANcoder> module) {
|
||||
this.moduleConstant = moduleConstant;
|
||||
this.moduleSimulation = moduleSimulation;
|
||||
moduleSimulation.useDriveMotorController(new TalonFXMotorControllerSim(module.getDriveMotor()));
|
||||
moduleSimulation.useSteerMotorController(
|
||||
new TalonFXMotorControllerWithRemoteCanCoderSim(module.getSteerMotor(), module.getEncoder()));
|
||||
}
|
||||
}
|
||||
|
||||
// Static utils classes
|
||||
public static class TalonFXMotorControllerSim implements SimulatedMotorController {
|
||||
public final int id;
|
||||
|
||||
private final TalonFXSimState talonFXSimState;
|
||||
|
||||
public TalonFXMotorControllerSim(TalonFX talonFX) {
|
||||
this.id = talonFX.getDeviceID();
|
||||
this.talonFXSimState = talonFX.getSimState();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Voltage updateControlSignal(
|
||||
Angle mechanismAngle,
|
||||
AngularVelocity mechanismVelocity,
|
||||
Angle encoderAngle,
|
||||
AngularVelocity encoderVelocity) {
|
||||
talonFXSimState.setRawRotorPosition(encoderAngle);
|
||||
talonFXSimState.setRotorVelocity(encoderVelocity);
|
||||
talonFXSimState.setSupplyVoltage(SimulatedBattery.getBatteryVoltage());
|
||||
|
||||
return talonFXSimState.getMotorVoltageMeasure();
|
||||
}
|
||||
}
|
||||
|
||||
public static class TalonFXMotorControllerWithRemoteCanCoderSim extends TalonFXMotorControllerSim {
|
||||
@SuppressWarnings("unused")
|
||||
private final int encoderId;
|
||||
private final CANcoderSimState remoteCancoderSimState;
|
||||
|
||||
public TalonFXMotorControllerWithRemoteCanCoderSim(TalonFX talonFX, CANcoder cancoder) {
|
||||
super(talonFX);
|
||||
this.remoteCancoderSimState = cancoder.getSimState();
|
||||
|
||||
this.encoderId = cancoder.getDeviceID();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Voltage updateControlSignal(
|
||||
Angle mechanismAngle,
|
||||
AngularVelocity mechanismVelocity,
|
||||
Angle encoderAngle,
|
||||
AngularVelocity encoderVelocity) {
|
||||
remoteCancoderSimState.setSupplyVoltage(SimulatedBattery.getBatteryVoltage());
|
||||
remoteCancoderSimState.setRawPosition(mechanismAngle);
|
||||
remoteCancoderSimState.setVelocity(mechanismVelocity);
|
||||
|
||||
return super.updateControlSignal(mechanismAngle, mechanismVelocity, encoderAngle, encoderVelocity);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
*
|
||||
*
|
||||
* <h2>Regulates all {@link SwerveModuleConstants} for a drivetrain
|
||||
* simulation.</h2>
|
||||
*
|
||||
* <p>
|
||||
* This method processes an array of {@link SwerveModuleConstants} to apply
|
||||
* necessary adjustments for simulation
|
||||
* purposes, ensuring compatibility and avoiding known bugs.
|
||||
*
|
||||
* @see #regulateModuleConstantForSimulation(SwerveModuleConstants)
|
||||
*/
|
||||
public static SwerveModuleConstants<?, ?, ?>[] regulateModuleConstantsForSimulation(
|
||||
SwerveModuleConstants<?, ?, ?>[] moduleConstants) {
|
||||
for (SwerveModuleConstants<?, ?, ?> moduleConstant : moduleConstants)
|
||||
regulateModuleConstantForSimulation(moduleConstant);
|
||||
|
||||
return moduleConstants;
|
||||
}
|
||||
|
||||
/**
|
||||
*
|
||||
*
|
||||
* <h2>Regulates the {@link SwerveModuleConstants} for a single module.</h2>
|
||||
*
|
||||
* <p>
|
||||
* This method applies specific adjustments to the {@link SwerveModuleConstants}
|
||||
* for simulation purposes. These
|
||||
* changes have no effect on real robot operations and address known simulation
|
||||
* bugs:
|
||||
*
|
||||
* <ul>
|
||||
* <li><strong>Inverted Drive Motors:</strong> Prevents drive PID issues caused
|
||||
* by inverted configurations.
|
||||
* <li><strong>Non-zero CanCoder Offsets:</strong> Fixes potential module state
|
||||
* optimization issues.
|
||||
* <li><strong>Steer Motor PID:</strong> Adjusts PID values tuned for real
|
||||
* robots to improve simulation
|
||||
* performance.
|
||||
* </ul>
|
||||
*
|
||||
* <h4>Note:This function is skipped when running on a real robot, ensuring no
|
||||
* impact on constants used on real
|
||||
* robot hardware.</h4>
|
||||
*/
|
||||
private static void regulateModuleConstantForSimulation(SwerveModuleConstants<?, ?, ?> moduleConstants) {
|
||||
// Skip regulation if running on a real robot
|
||||
if (RobotBase.isReal())
|
||||
return;
|
||||
|
||||
// Apply simulation-specific adjustments to module constants
|
||||
moduleConstants
|
||||
// Disable encoder offsets
|
||||
.withEncoderOffset(0)
|
||||
// Disable motor inversions for drive and steer motors
|
||||
.withDriveMotorInverted(false)
|
||||
.withSteerMotorInverted(false)
|
||||
// Disable CanCoder inversion
|
||||
.withEncoderInverted(false)
|
||||
// Adjust steer motor PID gains for simulation
|
||||
.withSteerMotorGains(new Slot0Configs()
|
||||
.withKP(70)
|
||||
.withKI(0)
|
||||
.withKD(4.5)
|
||||
.withKS(0)
|
||||
.withKV(1.91)
|
||||
.withKA(0)
|
||||
.withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign))
|
||||
.withSteerMotorGearRatio(16.0)
|
||||
// Adjust friction voltages
|
||||
.withDriveFrictionVoltage(Volts.of(0.1))
|
||||
.withSteerFrictionVoltage(Volts.of(0.05))
|
||||
// Adjust steer inertia
|
||||
.withSteerInertia(KilogramSquareMeters.of(0.05));
|
||||
}
|
||||
}
|
||||
@@ -3,7 +3,7 @@
|
||||
{
|
||||
"groupId": "com.github.jonahsnider",
|
||||
"artifactId": "doglog",
|
||||
"version": "2026.3.0"
|
||||
"version": "2026.5.0"
|
||||
}
|
||||
],
|
||||
"fileName": "DogLog.json",
|
||||
@@ -15,6 +15,6 @@
|
||||
"https://jitpack.io"
|
||||
],
|
||||
"cppDependencies": [],
|
||||
"version": "2026.3.0",
|
||||
"version": "2026.5.0",
|
||||
"uuid": "65592ce1-2251-4a31-8e4b-2df20dacebe4"
|
||||
}
|
||||
@@ -1,7 +1,7 @@
|
||||
{
|
||||
"fileName": "Phoenix6-frc2026-latest.json",
|
||||
"fileName": "Phoenix6-26.1.1.json",
|
||||
"name": "CTRE-Phoenix (v6)",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"frcYear": "2026",
|
||||
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
|
||||
"mavenUrls": [
|
||||
@@ -19,14 +19,14 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6",
|
||||
"artifactId": "wpiapi-java",
|
||||
"version": "26.1.0"
|
||||
"version": "26.1.1"
|
||||
}
|
||||
],
|
||||
"jniDependencies": [
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6",
|
||||
"artifactId": "api-cpp",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -40,7 +40,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6",
|
||||
"artifactId": "tools",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -54,7 +54,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "api-cpp-sim",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -68,7 +68,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "tools-sim",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -82,7 +82,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simTalonSRX",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -96,7 +96,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simVictorSPX",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -110,7 +110,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simPigeonIMU",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -124,7 +124,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProTalonFX",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -138,7 +138,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProTalonFXS",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -152,7 +152,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProCANcoder",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -166,7 +166,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProPigeon2",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -180,7 +180,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProCANrange",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -194,7 +194,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProCANdi",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -208,7 +208,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProCANdle",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"isJar": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"validPlatforms": [
|
||||
@@ -224,7 +224,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6",
|
||||
"artifactId": "wpiapi-cpp",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_Phoenix6_WPI",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -240,7 +240,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6",
|
||||
"artifactId": "tools",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_PhoenixTools",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -256,7 +256,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "wpiapi-cpp-sim",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_Phoenix6_WPISim",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -272,7 +272,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "tools-sim",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_PhoenixTools_Sim",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -288,7 +288,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simTalonSRX",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimTalonSRX",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -304,7 +304,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simVictorSPX",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimVictorSPX",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -320,7 +320,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simPigeonIMU",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimPigeonIMU",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -336,7 +336,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProTalonFX",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimProTalonFX",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -352,7 +352,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProTalonFXS",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimProTalonFXS",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -368,7 +368,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProCANcoder",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimProCANcoder",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -384,7 +384,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProPigeon2",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimProPigeon2",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -400,7 +400,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProCANrange",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimProCANrange",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -416,7 +416,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProCANdi",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimProCANdi",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
@@ -432,7 +432,7 @@
|
||||
{
|
||||
"groupId": "com.ctre.phoenix6.sim",
|
||||
"artifactId": "simProCANdle",
|
||||
"version": "26.1.0",
|
||||
"version": "26.1.1",
|
||||
"libName": "CTRE_SimProCANdle",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": true,
|
||||
133
vendordeps/REVLib.json
Normal file
133
vendordeps/REVLib.json
Normal file
@@ -0,0 +1,133 @@
|
||||
{
|
||||
"fileName": "REVLib.json",
|
||||
"name": "REVLib",
|
||||
"version": "2026.0.4",
|
||||
"frcYear": "2026",
|
||||
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
|
||||
"mavenUrls": [
|
||||
"https://maven.revrobotics.com/"
|
||||
],
|
||||
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2026.json",
|
||||
"javaDependencies": [
|
||||
{
|
||||
"groupId": "com.revrobotics.frc",
|
||||
"artifactId": "REVLib-java",
|
||||
"version": "2026.0.4"
|
||||
}
|
||||
],
|
||||
"jniDependencies": [
|
||||
{
|
||||
"groupId": "com.revrobotics.frc",
|
||||
"artifactId": "REVLib-driver",
|
||||
"version": "2026.0.4",
|
||||
"skipInvalidPlatforms": true,
|
||||
"isJar": false,
|
||||
"validPlatforms": [
|
||||
"windowsx86-64",
|
||||
"linuxarm64",
|
||||
"linuxx86-64",
|
||||
"linuxathena",
|
||||
"linuxarm32",
|
||||
"osxuniversal"
|
||||
]
|
||||
},
|
||||
{
|
||||
"groupId": "com.revrobotics.frc",
|
||||
"artifactId": "RevLibBackendDriver",
|
||||
"version": "2026.0.4",
|
||||
"skipInvalidPlatforms": true,
|
||||
"isJar": false,
|
||||
"validPlatforms": [
|
||||
"windowsx86-64",
|
||||
"linuxarm64",
|
||||
"linuxx86-64",
|
||||
"linuxathena",
|
||||
"linuxarm32",
|
||||
"osxuniversal"
|
||||
]
|
||||
},
|
||||
{
|
||||
"groupId": "com.revrobotics.frc",
|
||||
"artifactId": "RevLibWpiBackendDriver",
|
||||
"version": "2026.0.4",
|
||||
"skipInvalidPlatforms": true,
|
||||
"isJar": false,
|
||||
"validPlatforms": [
|
||||
"windowsx86-64",
|
||||
"linuxarm64",
|
||||
"linuxx86-64",
|
||||
"linuxathena",
|
||||
"linuxarm32",
|
||||
"osxuniversal"
|
||||
]
|
||||
}
|
||||
],
|
||||
"cppDependencies": [
|
||||
{
|
||||
"groupId": "com.revrobotics.frc",
|
||||
"artifactId": "REVLib-cpp",
|
||||
"version": "2026.0.4",
|
||||
"libName": "REVLib",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"binaryPlatforms": [
|
||||
"windowsx86-64",
|
||||
"linuxarm64",
|
||||
"linuxx86-64",
|
||||
"linuxathena",
|
||||
"linuxarm32",
|
||||
"osxuniversal"
|
||||
]
|
||||
},
|
||||
{
|
||||
"groupId": "com.revrobotics.frc",
|
||||
"artifactId": "REVLib-driver",
|
||||
"version": "2026.0.4",
|
||||
"libName": "REVLibDriver",
|
||||
"headerClassifier": "headers",
|
||||
"sharedLibrary": false,
|
||||
"skipInvalidPlatforms": true,
|
||||
"binaryPlatforms": [
|
||||
"windowsx86-64",
|
||||
"linuxarm64",
|
||||
"linuxx86-64",
|
||||
"linuxathena",
|
||||
"linuxarm32",
|
||||
"osxuniversal"
|
||||
]
|
||||
},
|
||||
{
|
||||
"groupId": "com.revrobotics.frc",
|
||||
"artifactId": "RevLibBackendDriver",
|
||||
"version": "2026.0.4",
|
||||
"libName": "BackendDriver",
|
||||
"sharedLibrary": true,
|
||||
"skipInvalidPlatforms": true,
|
||||
"binaryPlatforms": [
|
||||
"windowsx86-64",
|
||||
"linuxarm64",
|
||||
"linuxx86-64",
|
||||
"linuxathena",
|
||||
"linuxarm32",
|
||||
"osxuniversal"
|
||||
]
|
||||
},
|
||||
{
|
||||
"groupId": "com.revrobotics.frc",
|
||||
"artifactId": "RevLibWpiBackendDriver",
|
||||
"version": "2026.0.4",
|
||||
"libName": "REVLibWpi",
|
||||
"sharedLibrary": true,
|
||||
"skipInvalidPlatforms": true,
|
||||
"binaryPlatforms": [
|
||||
"windowsx86-64",
|
||||
"linuxarm64",
|
||||
"linuxx86-64",
|
||||
"linuxathena",
|
||||
"linuxarm32",
|
||||
"osxuniversal"
|
||||
]
|
||||
}
|
||||
]
|
||||
}
|
||||
26
vendordeps/maple-sim.json
Normal file
26
vendordeps/maple-sim.json
Normal file
@@ -0,0 +1,26 @@
|
||||
{
|
||||
"fileName": "maple-sim.json",
|
||||
"name": "maplesim",
|
||||
"version": "0.4.0-beta",
|
||||
"frcYear": "2026",
|
||||
"uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b",
|
||||
"mavenUrls": [
|
||||
"https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/repos/releases",
|
||||
"https://repo1.maven.org/maven2"
|
||||
],
|
||||
"jsonUrl": "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/maple-sim.json",
|
||||
"javaDependencies": [
|
||||
{
|
||||
"groupId": "org.ironmaple",
|
||||
"artifactId": "maplesim-java",
|
||||
"version": "0.4.0-beta"
|
||||
},
|
||||
{
|
||||
"groupId": "org.dyn4j",
|
||||
"artifactId": "dyn4j",
|
||||
"version": "5.0.2"
|
||||
}
|
||||
],
|
||||
"jniDependencies": [],
|
||||
"cppDependencies": []
|
||||
}
|
||||
Reference in New Issue
Block a user