mirror of
https://github.com/Astatin3/Vision-Minibot.git
synced 2026-06-09 00:28:05 -06:00
Fix tank drive mode
This commit is contained in:
@@ -48,23 +48,27 @@ public final class Constants {
|
|||||||
}
|
}
|
||||||
|
|
||||||
public static final class IDs {
|
public static final class IDs {
|
||||||
public static final int RIGHT_FRONT_WHEEL_ID = 2;
|
public static final int FR_ID = 22;
|
||||||
public static final int RIGHT_FRONT_STEER_ID = 3;
|
public static final int FL_ID = 20;
|
||||||
public static final int RIGHT_FRONT_ENCODER_ID = 10;
|
public static final int BL_ID = 21;
|
||||||
|
public static final int BR_ID = 23;
|
||||||
|
// public static final int RIGHT_FRONT_WHEEL_ID = 2;
|
||||||
|
// public static final int RIGHT_FRONT_STEER_ID = 3;
|
||||||
|
// public static final int RIGHT_FRONT_ENCODER_ID = 10;
|
||||||
|
|
||||||
public static final int LEFT_FRONT_WHEEL_ID = 4;
|
// public static final int LEFT_FRONT_WHEEL_ID = 4;
|
||||||
public static final int LEFT_FRONT_STEER_ID = 5;
|
// public static final int LEFT_FRONT_STEER_ID = 5;
|
||||||
public static final int LEFT_FRONT_ENCODER_ID = 11;
|
// public static final int LEFT_FRONT_ENCODER_ID = 11;
|
||||||
|
|
||||||
public static final int LEFT_BACK_WHEEL_ID = 6;
|
// public static final int LEFT_BACK_WHEEL_ID = 6;
|
||||||
public static final int LEFT_BACK_STEER_ID = 7;
|
// public static final int LEFT_BACK_STEER_ID = 7;
|
||||||
public static final int LEFT_BACK_ENCODER_ID = 12;
|
// public static final int LEFT_BACK_ENCODER_ID = 12;
|
||||||
|
|
||||||
public static final int RIGHT_BACK_WHEEL_ID = 8;
|
// public static final int RIGHT_BACK_WHEEL_ID = 8;
|
||||||
public static final int RIGHT_BACK_STEER_ID = 9;
|
// public static final int RIGHT_BACK_STEER_ID = 9;
|
||||||
public static final int RIGHT_BACK_ENCODER_ID = 13;
|
// public static final int RIGHT_BACK_ENCODER_ID = 13;
|
||||||
|
|
||||||
public static final int DRIVE_PIGEON_ID = 14;
|
// public static final int DRIVE_PIGEON_ID = 14;
|
||||||
}
|
}
|
||||||
|
|
||||||
public static final class PIDConstants {
|
public static final class PIDConstants {
|
||||||
@@ -143,7 +147,7 @@ public final class Constants {
|
|||||||
public static final int XBOX_DRIVER_ID = 0;
|
public static final int XBOX_DRIVER_ID = 0;
|
||||||
public static final int XBOX_OPERATOR_ID = 1;
|
public static final int XBOX_OPERATOR_ID = 1;
|
||||||
public static final int XBOX_PROGRAMMER_ID = 2;
|
public static final int XBOX_PROGRAMMER_ID = 2;
|
||||||
public static final double LEFT_AXIS_DEADBAND = 0.1;
|
public static final double LEFT_AXIS_DEADBAND = 0.20;
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -48,12 +48,12 @@ public class RobotContainer {
|
|||||||
/* Subsystems */
|
/* Subsystems */
|
||||||
// private final LED m_robotLED = new LED();
|
// private final LED m_robotLED = new LED();
|
||||||
|
|
||||||
public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.leftFront,
|
// public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.leftFront,
|
||||||
m_robotMap.rightFront,
|
// m_robotMap.rightFront,
|
||||||
m_robotMap.leftBack,
|
// m_robotMap.leftBack,
|
||||||
m_robotMap.rightBack,
|
// m_robotMap.rightBack,
|
||||||
|
|
||||||
m_robotMap.gyro);
|
// m_robotMap.gyro);
|
||||||
|
|
||||||
/* Controllers */
|
/* Controllers */
|
||||||
private final DeadbandedXboxController m_driverXbox = new DeadbandedXboxController(OIConstants.XBOX_DRIVER_ID);
|
private final DeadbandedXboxController m_driverXbox = new DeadbandedXboxController(OIConstants.XBOX_DRIVER_ID);
|
||||||
@@ -69,10 +69,10 @@ public class RobotContainer {
|
|||||||
// ! /* Autos */
|
// ! /* Autos */
|
||||||
private String lastAutoName = "defualt.auto";
|
private String lastAutoName = "defualt.auto";
|
||||||
private ConfigurableString autoplaybackName = new ConfigurableString("Auto Playback Name", lastAutoName);
|
private ConfigurableString autoplaybackName = new ConfigurableString("Auto Playback Name", lastAutoName);
|
||||||
private neoJoystickPlayback autoPlayback = new neoJoystickPlayback(m_robotSwerveDrive,
|
// private neoJoystickPlayback autoPlayback = new neoJoystickPlayback(m_robotSwerveDrive,
|
||||||
() -> autoplaybackName.get(), // lastAutoName
|
// () -> autoplaybackName.get(), // lastAutoName
|
||||||
new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()},
|
// new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()},
|
||||||
true, false);
|
// true, false);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* The container for the robot. Contains subsystems, OI devices, and commands.
|
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||||
@@ -80,20 +80,20 @@ public class RobotContainer {
|
|||||||
public RobotContainer() {
|
public RobotContainer() {
|
||||||
configureButtonBindings();
|
configureButtonBindings();
|
||||||
configureVirtualButtonBindings();
|
configureVirtualButtonBindings();
|
||||||
new DeferredBlock(() -> m_robotSwerveDrive.resetGyroFlip());
|
// new DeferredBlock(() -> m_robotSwerveDrive.resetGyroFlip());
|
||||||
DriverStation.silenceJoystickConnectionWarning(true);
|
DriverStation.silenceJoystickConnectionWarning(true);
|
||||||
// CameraServer.startAutomaticCapture();
|
// CameraServer.startAutomaticCapture();
|
||||||
|
|
||||||
/* Default Commands */
|
/* Default Commands */
|
||||||
// ! Swerve Drive Default Command (Regular Rotation)
|
// ! Swerve Drive Default Command (Regular Rotation)
|
||||||
// drives the robot with a two-axis input from the driver controller
|
// drives the robot with a two-axis input from the driver controller
|
||||||
m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> {
|
m_robotMap.tankDrive.setDefaultCommand(new RunCommand(() -> {
|
||||||
m_robotSwerveDrive.driveWithInput(getDeadbandedDriverController().getLeft(),
|
m_robotMap.tankDrive.driveWithInput(getDeadbandedDriverController().getLeft(),
|
||||||
getDeadbandedDriverController().getRight(),
|
getDeadbandedDriverController().getRight(),
|
||||||
true);
|
true);
|
||||||
}, m_robotSwerveDrive)
|
}, m_robotMap.tankDrive)
|
||||||
.withName("SwerveDrive DefaultCommand"));
|
.withName("SwerveDrive DefaultCommand"));
|
||||||
m_robotSwerveDrive.setToSlow();
|
// m_robotMap.tankDrive.setToSlow();
|
||||||
|
|
||||||
// ! Swerve Drive One Module Test
|
// ! Swerve Drive One Module Test
|
||||||
// m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> {
|
// m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> {
|
||||||
@@ -133,39 +133,39 @@ public class RobotContainer {
|
|||||||
|
|
||||||
// ? /* Driver Buttons */
|
// ? /* Driver Buttons */
|
||||||
|
|
||||||
DualJoystickButton(getDeadbandedDriverController(), getVirtualDriverController(), XboxController.A_BUTTON)
|
// DualJoystickButton(getDeadbandedDriverController(), getVirtualDriverController(), XboxController.A_BUTTON)
|
||||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip()));
|
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip()));
|
||||||
|
|
||||||
// ! /* Speed */
|
// // ! /* Speed */
|
||||||
new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // final
|
// new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // final
|
||||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUp()));
|
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUp()));
|
||||||
|
|
||||||
new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON) // final
|
// new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON) // final
|
||||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDown()));
|
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDown()));
|
||||||
|
|
||||||
new Trigger(() -> getDeadbandedDriverController().getPOV() == 270)
|
// new Trigger(() -> getDeadbandedDriverController().getPOV() == 270)
|
||||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDownRot()));
|
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDownRot()));
|
||||||
|
|
||||||
new Trigger(() -> getDeadbandedDriverController().getPOV() == 90)
|
// new Trigger(() -> getDeadbandedDriverController().getPOV() == 90)
|
||||||
.onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUpRot()));
|
// .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUpRot()));
|
||||||
|
|
||||||
// ? /* Operator Buttons */
|
// ? /* Operator Buttons */
|
||||||
|
|
||||||
// ? /* Programer Buttons (Controller 3)*/
|
// ? /* Programer Buttons (Controller 3)*/
|
||||||
|
|
||||||
// * /* Auto Recording */
|
// * /* Auto Recording */
|
||||||
new JoystickButton(m_autoRecorderXbox, XboxController.LEFT_BUMPER_BUTTON)
|
// new JoystickButton(m_autoRecorderXbox, XboxController.LEFT_BUMPER_BUTTON)
|
||||||
.whileTrue(new neoJoystickRecorder(m_robotSwerveDrive,
|
// .whileTrue(new neoJoystickRecorder(m_robotSwerveDrive,
|
||||||
new DeadbandedXboxController[]{getDeadbandedDriverController(), getDeadbandedOperatorController()},
|
// new DeadbandedXboxController[]{getDeadbandedDriverController(), getDeadbandedOperatorController()},
|
||||||
() -> autoplaybackName.get()))
|
// () -> autoplaybackName.get()))
|
||||||
.onFalse(new InstantCommand());
|
// .onFalse(new InstantCommand());
|
||||||
|
|
||||||
new JoystickButton(m_autoRecorderXbox, XboxController.RIGHT_BUMPER_BUTTON)
|
// new JoystickButton(m_autoRecorderXbox, XboxController.RIGHT_BUMPER_BUTTON)
|
||||||
.onTrue(new neoJoystickPlayback(m_robotSwerveDrive,
|
// .onTrue(new neoJoystickPlayback(m_robotSwerveDrive,
|
||||||
() -> autoplaybackName.get(),
|
// () -> autoplaybackName.get(),
|
||||||
new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()},
|
// new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()},
|
||||||
true, false))
|
// true, false))
|
||||||
.onFalse(new InstantCommand());
|
// .onFalse(new InstantCommand());
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -200,7 +200,10 @@ public class RobotContainer {
|
|||||||
* @return the command to run in autonomous
|
* @return the command to run in autonomous
|
||||||
*/
|
*/
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
return autoPlayback;
|
// return autoPlayback;
|
||||||
|
return new Command() {
|
||||||
|
|
||||||
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|||||||
@@ -8,6 +8,7 @@
|
|||||||
package frc4388.robot;
|
package frc4388.robot;
|
||||||
|
|
||||||
import com.ctre.phoenix6.hardware.TalonFX;
|
import com.ctre.phoenix6.hardware.TalonFX;
|
||||||
|
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
|
||||||
import com.ctre.phoenix6.hardware.CANcoder;
|
import com.ctre.phoenix6.hardware.CANcoder;
|
||||||
import com.ctre.phoenix6.hardware.Pigeon2;
|
import com.ctre.phoenix6.hardware.Pigeon2;
|
||||||
|
|
||||||
@@ -15,6 +16,7 @@ import com.ctre.phoenix6.hardware.Pigeon2;
|
|||||||
// import frc4388.robot.Constants.LEDConstants;
|
// import frc4388.robot.Constants.LEDConstants;
|
||||||
import frc4388.robot.Constants.SwerveDriveConstants;
|
import frc4388.robot.Constants.SwerveDriveConstants;
|
||||||
import frc4388.robot.subsystems.SwerveModule;
|
import frc4388.robot.subsystems.SwerveModule;
|
||||||
|
import frc4388.robot.subsystems.TankDrive;
|
||||||
import frc4388.utility.RobotGyro;
|
import frc4388.utility.RobotGyro;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -22,44 +24,52 @@ import frc4388.utility.RobotGyro;
|
|||||||
* testing and modularization.
|
* testing and modularization.
|
||||||
*/
|
*/
|
||||||
public class RobotMap {
|
public class RobotMap {
|
||||||
private Pigeon2 m_pigeon2 = new Pigeon2(SwerveDriveConstants.IDs.DRIVE_PIGEON_ID);
|
// private Pigeon2 m_pigeon2 = new Pigeon2(SwerveDriveConstants.IDs.DRIVE_PIGEON_ID);
|
||||||
public RobotGyro gyro = new RobotGyro(m_pigeon2);
|
// public RobotGyro gyro = new RobotGyro(m_pigeon2);
|
||||||
|
|
||||||
public SwerveModule leftFront;
|
// public SwerveModule leftFront;
|
||||||
public SwerveModule rightFront;
|
// public SwerveModule rightFront;
|
||||||
public SwerveModule leftBack;
|
// public SwerveModule leftBack;
|
||||||
public SwerveModule rightBack;
|
// public SwerveModule rightBack;
|
||||||
|
|
||||||
public RobotMap() {
|
public RobotMap() {
|
||||||
configureDriveMotorControllers();
|
configureDriveMotorControllers();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public final TalonSRX FR = new TalonSRX(SwerveDriveConstants.IDs.FR_ID);
|
||||||
|
public final TalonSRX FL = new TalonSRX(SwerveDriveConstants.IDs.FL_ID);
|
||||||
|
public final TalonSRX BL = new TalonSRX(SwerveDriveConstants.IDs.BL_ID);
|
||||||
|
public final TalonSRX BR = new TalonSRX(SwerveDriveConstants.IDs.BR_ID);
|
||||||
|
|
||||||
|
public TankDrive tankDrive;
|
||||||
|
|
||||||
/* LED Subsystem */
|
/* LED Subsystem */
|
||||||
// public final Spark LEDController = new Spark(LEDConstants.LED_SPARK_ID);
|
// public final Spark LEDController = new Spark(LEDConstants.LED_SPARK_ID);
|
||||||
|
|
||||||
/* Swreve Drive Subsystem */
|
/* Swreve Drive Subsystem */
|
||||||
public final TalonFX leftFrontWheel = new TalonFX(SwerveDriveConstants.IDs.LEFT_FRONT_WHEEL_ID);
|
// public final TalonFX leftFrontWheel = new TalonFX(SwerveDriveConstants.IDs.LEFT_FRONT_WHEEL_ID);
|
||||||
public final TalonFX leftFrontSteer = new TalonFX(SwerveDriveConstants.IDs.LEFT_FRONT_STEER_ID);
|
// public final TalonFX leftFrontSteer = new TalonFX(SwerveDriveConstants.IDs.LEFT_FRONT_STEER_ID);
|
||||||
public final CANcoder leftFrontEncoder = new CANcoder(SwerveDriveConstants.IDs.LEFT_FRONT_ENCODER_ID);
|
// public final CANcoder leftFrontEncoder = new CANcoder(SwerveDriveConstants.IDs.LEFT_FRONT_ENCODER_ID);
|
||||||
|
|
||||||
|
|
||||||
public final TalonFX rightFrontWheel = new TalonFX(SwerveDriveConstants.IDs.RIGHT_FRONT_WHEEL_ID);
|
// public final TalonFX rightFrontWheel = new TalonFX(SwerveDriveConstants.IDs.RIGHT_FRONT_WHEEL_ID);
|
||||||
public final TalonFX rightFrontSteer = new TalonFX(SwerveDriveConstants.IDs.RIGHT_FRONT_STEER_ID);
|
// public final TalonFX rightFrontSteer = new TalonFX(SwerveDriveConstants.IDs.RIGHT_FRONT_STEER_ID);
|
||||||
public final CANcoder rightFrontEncoder = new CANcoder(SwerveDriveConstants.IDs.RIGHT_FRONT_ENCODER_ID);
|
// public final CANcoder rightFrontEncoder = new CANcoder(SwerveDriveConstants.IDs.RIGHT_FRONT_ENCODER_ID);
|
||||||
|
|
||||||
public final TalonFX leftBackWheel = new TalonFX(SwerveDriveConstants.IDs.LEFT_BACK_WHEEL_ID);
|
// public final TalonFX leftBackWheel = new TalonFX(SwerveDriveConstants.IDs.LEFT_BACK_WHEEL_ID);
|
||||||
public final TalonFX leftBackSteer = new TalonFX(SwerveDriveConstants.IDs.LEFT_BACK_STEER_ID);
|
// public final TalonFX leftBackSteer = new TalonFX(SwerveDriveConstants.IDs.LEFT_BACK_STEER_ID);
|
||||||
public final CANcoder leftBackEncoder = new CANcoder(SwerveDriveConstants.IDs.LEFT_BACK_ENCODER_ID);
|
// public final CANcoder leftBackEncoder = new CANcoder(SwerveDriveConstants.IDs.LEFT_BACK_ENCODER_ID);
|
||||||
|
|
||||||
public final TalonFX rightBackWheel = new TalonFX(SwerveDriveConstants.IDs.RIGHT_BACK_WHEEL_ID);
|
// public final TalonFX rightBackWheel = new TalonFX(SwerveDriveConstants.IDs.RIGHT_BACK_WHEEL_ID);
|
||||||
public final TalonFX rightBackSteer = new TalonFX(SwerveDriveConstants.IDs.RIGHT_BACK_STEER_ID);
|
// public final TalonFX rightBackSteer = new TalonFX(SwerveDriveConstants.IDs.RIGHT_BACK_STEER_ID);
|
||||||
public final CANcoder rightBackEncoder = new CANcoder(SwerveDriveConstants.IDs.RIGHT_BACK_ENCODER_ID);
|
// public final CANcoder rightBackEncoder = new CANcoder(SwerveDriveConstants.IDs.RIGHT_BACK_ENCODER_ID);
|
||||||
|
|
||||||
void configureDriveMotorControllers() {
|
void configureDriveMotorControllers() {
|
||||||
|
this.tankDrive = new TankDrive(FR, FL, BL, BR);
|
||||||
// initialize SwerveModules
|
// initialize SwerveModules
|
||||||
this.rightFront = new SwerveModule(rightFrontWheel, rightFrontSteer, rightFrontEncoder, SwerveDriveConstants.DefaultSwerveRotOffsets.FRONT_RIGHT_ROT_OFFSET);
|
// this.rightFront = new SwerveModule(rightFrontWheel, rightFrontSteer, rightFrontEncoder, SwerveDriveConstants.DefaultSwerveRotOffsets.FRONT_RIGHT_ROT_OFFSET);
|
||||||
this.leftFront = new SwerveModule(leftFrontWheel, leftFrontSteer, leftFrontEncoder, SwerveDriveConstants.DefaultSwerveRotOffsets.FRONT_LEFT_ROT_OFFSET);
|
// this.leftFront = new SwerveModule(leftFrontWheel, leftFrontSteer, leftFrontEncoder, SwerveDriveConstants.DefaultSwerveRotOffsets.FRONT_LEFT_ROT_OFFSET);
|
||||||
this.leftBack = new SwerveModule(leftBackWheel, leftBackSteer, leftBackEncoder, SwerveDriveConstants.DefaultSwerveRotOffsets.BACK_LEFT_ROT_OFFSET);
|
// this.leftBack = new SwerveModule(leftBackWheel, leftBackSteer, leftBackEncoder, SwerveDriveConstants.DefaultSwerveRotOffsets.BACK_LEFT_ROT_OFFSET);
|
||||||
this.rightBack = new SwerveModule(rightBackWheel, rightBackSteer, rightBackEncoder, SwerveDriveConstants.DefaultSwerveRotOffsets.BACK_RIGHT_ROT_OFFSET);
|
// this.rightBack = new SwerveModule(rightBackWheel, rightBackSteer, rightBackEncoder, SwerveDriveConstants.DefaultSwerveRotOffsets.BACK_RIGHT_ROT_OFFSET);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -4,6 +4,7 @@ import com.ctre.phoenix.motorcontrol.ControlMode;
|
|||||||
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
|
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
|
||||||
|
|
||||||
import edu.wpi.first.math.geometry.Translation2d;
|
import edu.wpi.first.math.geometry.Translation2d;
|
||||||
|
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|
||||||
public class TankDrive extends SubsystemBase{
|
public class TankDrive extends SubsystemBase{
|
||||||
@@ -21,20 +22,22 @@ public class TankDrive extends SubsystemBase{
|
|||||||
|
|
||||||
private static final ControlMode mode = ControlMode.PercentOutput;
|
private static final ControlMode mode = ControlMode.PercentOutput;
|
||||||
|
|
||||||
private static final double maxSpeed = 1.;
|
private static final double maxMoveSpeed = 0.6;
|
||||||
|
private static final double maxturnSpeed = 0.6;
|
||||||
|
|
||||||
private static final double[] turn = { //Right by default
|
|
||||||
-maxSpeed, //FR
|
private static final double[] turn = { //Right by default, motors are wired weirdly
|
||||||
maxSpeed, //FL
|
maxturnSpeed, //FR
|
||||||
maxSpeed, //BL
|
maxturnSpeed, //FL
|
||||||
-maxSpeed, //BR
|
maxturnSpeed, //BL
|
||||||
|
maxturnSpeed, //BR
|
||||||
};
|
};
|
||||||
|
|
||||||
private static final double[] move = { //forward by default
|
private static final double[] move = { //forward by default, motors are wired weirdly
|
||||||
maxSpeed, //FR
|
-maxMoveSpeed, //FR
|
||||||
maxSpeed, //FL
|
maxMoveSpeed, //FL
|
||||||
maxSpeed, //BL
|
maxMoveSpeed, //BL
|
||||||
maxSpeed, //BR
|
-maxMoveSpeed, //BR
|
||||||
};
|
};
|
||||||
|
|
||||||
public void driveWithInput(Translation2d leftStick, Translation2d rightStick, boolean fieldRelative) {
|
public void driveWithInput(Translation2d leftStick, Translation2d rightStick, boolean fieldRelative) {
|
||||||
@@ -50,5 +53,10 @@ public class TankDrive extends SubsystemBase{
|
|||||||
FL.set(mode, FL_rot);
|
FL.set(mode, FL_rot);
|
||||||
BL.set(mode, BL_rot);
|
BL.set(mode, BL_rot);
|
||||||
BR.set(mode, BR_rot);
|
BR.set(mode, BR_rot);
|
||||||
|
|
||||||
|
SmartDashboard.putNumber("FR", FR_rot);
|
||||||
|
SmartDashboard.putNumber("FL", FL_rot);
|
||||||
|
SmartDashboard.putNumber("BL", BL_rot);
|
||||||
|
SmartDashboard.putNumber("BR", BR_rot);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
+21
-293
@@ -1,30 +1,38 @@
|
|||||||
{
|
{
|
||||||
"fileName": "Phoenix.json",
|
"fileName": "Phoenix5.json",
|
||||||
"name": "CTRE-Phoenix (v5)",
|
"name": "CTRE-Phoenix (v5)",
|
||||||
"version": "5.31.0+23.2.2",
|
"version": "5.33.1",
|
||||||
"frcYear": 2024,
|
"frcYear": 2024,
|
||||||
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
|
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
|
||||||
"mavenUrls": [
|
"mavenUrls": [
|
||||||
"https://maven.ctr-electronics.com/release/"
|
"https://maven.ctr-electronics.com/release/"
|
||||||
],
|
],
|
||||||
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2023-latest.json",
|
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2024-latest.json",
|
||||||
|
"requires": [
|
||||||
|
{
|
||||||
|
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
|
||||||
|
"errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.",
|
||||||
|
"offlineFileName": "Phoenix6.json",
|
||||||
|
"onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json"
|
||||||
|
}
|
||||||
|
],
|
||||||
"javaDependencies": [
|
"javaDependencies": [
|
||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix",
|
"groupId": "com.ctre.phoenix",
|
||||||
"artifactId": "api-java",
|
"artifactId": "api-java",
|
||||||
"version": "5.31.0"
|
"version": "5.33.1"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix",
|
"groupId": "com.ctre.phoenix",
|
||||||
"artifactId": "wpiapi-java",
|
"artifactId": "wpiapi-java",
|
||||||
"version": "5.31.0"
|
"version": "5.33.1"
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
"jniDependencies": [
|
"jniDependencies": [
|
||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix",
|
"groupId": "com.ctre.phoenix",
|
||||||
"artifactId": "cci",
|
"artifactId": "cci",
|
||||||
"version": "5.31.0",
|
"version": "5.33.1",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -37,137 +45,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix.sim",
|
"groupId": "com.ctre.phoenix.sim",
|
||||||
"artifactId": "cci-sim",
|
"artifactId": "cci-sim",
|
||||||
"version": "5.31.0",
|
"version": "5.33.1",
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6",
|
|
||||||
"artifactId": "tools",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"linuxathena"
|
|
||||||
],
|
|
||||||
"simMode": "hwsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "tools-sim",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simTalonSRX",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simTalonFX",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simVictorSPX",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simPigeonIMU",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simCANCoder",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simProTalonFX",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simProCANcoder",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"validPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simProPigeon2",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -182,7 +60,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix",
|
"groupId": "com.ctre.phoenix",
|
||||||
"artifactId": "wpiapi-cpp",
|
"artifactId": "wpiapi-cpp",
|
||||||
"version": "5.31.0",
|
"version": "5.33.1",
|
||||||
"libName": "CTRE_Phoenix_WPI",
|
"libName": "CTRE_Phoenix_WPI",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -197,7 +75,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix",
|
"groupId": "com.ctre.phoenix",
|
||||||
"artifactId": "api-cpp",
|
"artifactId": "api-cpp",
|
||||||
"version": "5.31.0",
|
"version": "5.33.1",
|
||||||
"libName": "CTRE_Phoenix",
|
"libName": "CTRE_Phoenix",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -212,7 +90,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix",
|
"groupId": "com.ctre.phoenix",
|
||||||
"artifactId": "cci",
|
"artifactId": "cci",
|
||||||
"version": "5.31.0",
|
"version": "5.33.1",
|
||||||
"libName": "CTRE_PhoenixCCI",
|
"libName": "CTRE_PhoenixCCI",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -224,25 +102,10 @@
|
|||||||
],
|
],
|
||||||
"simMode": "hwsim"
|
"simMode": "hwsim"
|
||||||
},
|
},
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6",
|
|
||||||
"artifactId": "tools",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_PhoenixTools",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"linuxathena"
|
|
||||||
],
|
|
||||||
"simMode": "hwsim"
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix.sim",
|
"groupId": "com.ctre.phoenix.sim",
|
||||||
"artifactId": "wpiapi-cpp-sim",
|
"artifactId": "wpiapi-cpp-sim",
|
||||||
"version": "5.31.0",
|
"version": "5.33.1",
|
||||||
"libName": "CTRE_Phoenix_WPISim",
|
"libName": "CTRE_Phoenix_WPISim",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -257,7 +120,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix.sim",
|
"groupId": "com.ctre.phoenix.sim",
|
||||||
"artifactId": "api-cpp-sim",
|
"artifactId": "api-cpp-sim",
|
||||||
"version": "5.31.0",
|
"version": "5.33.1",
|
||||||
"libName": "CTRE_PhoenixSim",
|
"libName": "CTRE_PhoenixSim",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -272,7 +135,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix.sim",
|
"groupId": "com.ctre.phoenix.sim",
|
||||||
"artifactId": "cci-sim",
|
"artifactId": "cci-sim",
|
||||||
"version": "5.31.0",
|
"version": "5.33.1",
|
||||||
"libName": "CTRE_PhoenixCCISim",
|
"libName": "CTRE_PhoenixCCISim",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -283,141 +146,6 @@
|
|||||||
"osxuniversal"
|
"osxuniversal"
|
||||||
],
|
],
|
||||||
"simMode": "swsim"
|
"simMode": "swsim"
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "tools-sim",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_PhoenixTools_Sim",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simTalonSRX",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_SimTalonSRX",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simTalonFX",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_SimTalonFX",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simVictorSPX",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_SimVictorSPX",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simPigeonIMU",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_SimPigeonIMU",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simCANCoder",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_SimCANCoder",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simProTalonFX",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_SimProTalonFX",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simProCANcoder",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_SimProCANcoder",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
},
|
|
||||||
{
|
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
|
||||||
"artifactId": "simProPigeon2",
|
|
||||||
"version": "23.2.2",
|
|
||||||
"libName": "CTRE_SimProPigeon2",
|
|
||||||
"headerClassifier": "headers",
|
|
||||||
"sharedLibrary": true,
|
|
||||||
"skipInvalidPlatforms": true,
|
|
||||||
"binaryPlatforms": [
|
|
||||||
"windowsx86-64",
|
|
||||||
"linuxx86-64",
|
|
||||||
"osxuniversal"
|
|
||||||
],
|
|
||||||
"simMode": "swsim"
|
|
||||||
}
|
}
|
||||||
]
|
]
|
||||||
}
|
}
|
||||||
Reference in New Issue
Block a user