diff --git a/src/main/java/frc/robot/Config.java b/src/main/java/frc/robot/Config.java index 0705e3d..06d5e6f 100644 --- a/src/main/java/frc/robot/Config.java +++ b/src/main/java/frc/robot/Config.java @@ -35,6 +35,20 @@ public final class Config { */ private static int robotId = -1; + /** + * CAN IDs, ports, channels, etc. + */ + public static class CANID { + // Arm Subsystem + public static final int TOP_ARM_SPARK_CAN_ID = robotSpecific(5,0,0,0,0,18,18); + public static final int BOTTOM_ARM_SPARK_CAN_ID = robotSpecific(4,0,0,0,0,19,19); + + //Arm Subsystem + public static final int BOTTOM_CANCODER_CAN_ID = 2; + + + } + /** * Returns one of the values passed based on the robot ID * @@ -94,12 +108,14 @@ public static int getRobotId() { /** ADD CONSTANTS BELOW THIS LINE */ - // PCM Can ID - public static final int CTRE_PCM_CAN_ID = 1; - // Constants for arm pneumatics - public static final int ARMLOW_PNEUMATIC_FORWARD_CHANNEL = 0; - public static final int ARMLOW_PNEUMATIC_REVERSE_CHANNEL = 1; + //PCM Can ID + public static final int CTRE_PCM_CAN_ID = 1; + + //Constants for arm pneumatics + public static final int ARMLOW_PNEUMATIC_FORWARD_CHANNEL=0; + public static final int ARMLOW_PNEUMATIC_REVERSE_CHANNEL = 1; + public static final int ARMHIGH_PNEUMATIC_FORWARD_CHANNEL = 2; public static final int ARMHIGH_PNEUMATIC_REVERSE_CHANNEL = 3; diff --git a/src/main/java/frc/robot/ErrorCheck.java b/src/main/java/frc/robot/ErrorCheck.java new file mode 100644 index 0000000..9ce8bfd --- /dev/null +++ b/src/main/java/frc/robot/ErrorCheck.java @@ -0,0 +1,25 @@ +package frc.robot; + +import com.ctre.phoenix.ErrorCode; +import com.revrobotics.REVLibError; + +import edu.wpi.first.wpilibj.DriverStation; + +public class ErrorCheck { + public static int count = -1; + public static boolean errREV(REVLibError error) { + if (error == REVLibError.kOk) { + return true; + } + DriverStation.reportError("REV DEVICE Error" + error.toString(), true); + return false; +} +public static boolean errCTRE(ErrorCode error) { + if (error == ErrorCode.OK) { + return true; + } + + DriverStation.reportError("CTRE Device Error: " + error.toString(), true); + return false; +} +} diff --git a/src/main/java/frc/robot/ProfiledPIDFFController.java b/src/main/java/frc/robot/ProfiledPIDFFController.java new file mode 100644 index 0000000..84e42db --- /dev/null +++ b/src/main/java/frc/robot/ProfiledPIDFFController.java @@ -0,0 +1,55 @@ +package frc.robot; + +import edu.wpi.first.math.controller.ProfiledPIDController; +import edu.wpi.first.math.controller.SimpleMotorFeedforward; +import edu.wpi.first.math.trajectory.TrapezoidProfile; +import edu.wpi.first.wpilibj.Timer; +import frc.robot.subsystems.ArmConfig; + +public class ProfiledPIDFFController { + private double lastVel = 0; + private double lastTime = Timer.getFPGATimestamp(); + + private final TrapezoidProfile.Constraints m_constraints = + new TrapezoidProfile.Constraints(ArmConfig.TOP_MAX_VEL, ArmConfig.TOP_MAX_ACCEL); + private final ProfiledPIDController m_ProfiledPIDController = + new ProfiledPIDController(1.6,0.002,40, m_constraints, 0.02); + + private final SimpleMotorFeedforward m_FFController = new SimpleMotorFeedforward(0,0); + + public ProfiledPIDFFController () + { + + } + + public void setFinalGoal( TrapezoidProfile.State finalGoal) + { + m_ProfiledPIDController.setGoal(finalGoal); + } + + public double getProfiledPIDVoltage (double measuredPos, double finalPos) + { + return m_ProfiledPIDController.calculate(measuredPos, finalPos); + } + + public double getProfiledPIDFFVoltage(double measuredPos, double finalPos) + { + double pidVal = getProfiledPIDVoltage(measuredPos, finalPos); + + double currVel = m_ProfiledPIDController.getSetpoint().velocity; + double currAccel = (m_ProfiledPIDController.getSetpoint().velocity - lastVel)/(Timer.getFPGATimestamp() - lastTime); + double ffVal = m_FFController.calculate(currVel, currAccel); + + lastVel = currVel; + lastTime = Timer.getFPGATimestamp(); + + return ffVal; + } + + public double getNextProfiledPIDPos(double measuredPos, double finalPos) { + double pidVal = getProfiledPIDVoltage(measuredPos, finalPos); + + double currPos = m_ProfiledPIDController.getSetpoint().position; + return currPos; + } +} diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 9fa643b..5b0a94d 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -8,6 +8,11 @@ import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; +import edu.wpi.first.wpilibj2.command.ScheduleCommand; +import edu.wpi.first.wpilibj2.command.WaitCommand; +import frc.robot.SubsystemChecker.SubsystemType; +import frc.robot.commands.CheckArmEncodersSync; +import frc.robot.commands.SyncArmEncoders; import frc.robot.robotcontainers.BeetleContainer; import frc.robot.robotcontainers.ClutchContainer; import frc.robot.robotcontainers.CosmobotContainer; @@ -33,6 +38,13 @@ public void robotInit() { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. createRobotContainer(); + + if (SubsystemChecker.canSubsystemConstruct(SubsystemType.ArmSubsystem)) { + System.out.println("*****robotInit*****"); + //new WaitCommand(10).andThen(new CheckArmEncodersSync()).schedule(); + new WaitCommand(10).andThen(new ScheduleCommand(new CheckArmEncodersSync())).schedule(); + } + } private void createRobotContainer() { diff --git a/src/main/java/frc/lib/lib2706/SubsystemChecker.java b/src/main/java/frc/robot/SubsystemChecker.java similarity index 98% rename from src/main/java/frc/lib/lib2706/SubsystemChecker.java rename to src/main/java/frc/robot/SubsystemChecker.java index e1e5949..3234c4a 100644 --- a/src/main/java/frc/lib/lib2706/SubsystemChecker.java +++ b/src/main/java/frc/robot/SubsystemChecker.java @@ -2,9 +2,7 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -package frc.lib.lib2706; - -import frc.robot.Config; +package frc.robot; /** Add your docs here. */ public class SubsystemChecker { diff --git a/src/main/java/frc/robot/commands/CheckArmEncodersSync.java b/src/main/java/frc/robot/commands/CheckArmEncodersSync.java new file mode 100644 index 0000000..e39170d --- /dev/null +++ b/src/main/java/frc/robot/commands/CheckArmEncodersSync.java @@ -0,0 +1,51 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands; + +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.ArmSubsystem; + +public class CheckArmEncodersSync extends CommandBase { + /** Creates a new CheckArmEncodersSync. */ + public CheckArmEncodersSync() { + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(ArmSubsystem.getInstance()); + + } + + // Called when the command is initially scheduled. + @Override + public void initialize() {} + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + if (ArmSubsystem.getInstance().areEncodersSynced()==false) { + DriverStation.reportWarning ("CheckArmEncoders: Arm encoders are not synced", false); + System.out.println("*****CheckArmEncoders: Arm encoders are not synced*****"); + } + else { + DriverStation.reportWarning ("CheckArmEncoders: Arm encoders are synced", false); + System.out.println("*****CheckArmEncoders: Arm encoders are synced*****"); + } + + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) {} + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return true; + } + + @Override + public boolean runsWhenDisabled() { + return true; + } +} diff --git a/src/main/java/frc/robot/commands/SetBottomArm.java b/src/main/java/frc/robot/commands/SetBottomArm.java new file mode 100644 index 0000000..5933662 --- /dev/null +++ b/src/main/java/frc/robot/commands/SetBottomArm.java @@ -0,0 +1,62 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands; + +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.ArmPneumaticsSubsystem; +import frc.robot.subsystems.ArmSubsystem; + +public class SetBottomArm extends CommandBase { + double bottomArmAngleRadians; + final double TIMEOUT_S=2; + + Timer m_timer = new Timer(); + /** Creates a new SetBottomArm. */ + public SetBottomArm(double angleDegree) { + bottomArmAngleRadians = Math.toRadians(angleDegree); + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(ArmSubsystem.getInstance()); + addRequirements(ArmPneumaticsSubsystem.getInstance()); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + //ArmSubsystem.getInstance().controlBottomArmBrake(false); + ArmPneumaticsSubsystem.getInstance().controlBottomBrake(false, false); + m_timer.stop(); + m_timer.reset(); + //todo: + m_timer.start(); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + ArmSubsystem.getInstance().setBottomJointAngle(bottomArmAngleRadians); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + ArmSubsystem.getInstance().stopMotors(); + if (interrupted == false) + { + //ArmSubsystem.getInstance().controlBottomArmBrake(true); + ArmPneumaticsSubsystem.getInstance().controlBottomBrake(true, true); + + } + m_timer.stop(); + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + //todo: check if bottom arm reaches the position + //time out, finished + return m_timer.hasElapsed(TIMEOUT_S); + } +} diff --git a/src/main/java/frc/robot/commands/SetTopArm.java b/src/main/java/frc/robot/commands/SetTopArm.java new file mode 100644 index 0000000..450ece4 --- /dev/null +++ b/src/main/java/frc/robot/commands/SetTopArm.java @@ -0,0 +1,48 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.ArmPneumaticsSubsystem; +import frc.robot.subsystems.ArmSubsystem; + +public class SetTopArm extends CommandBase{ + double topArmAngleRadians; + final double TIMEOUT_S= 1.5; + + Timer m_timer = new Timer(); + /*Creates a new SetTopArm */ + public SetTopArm(double angleDegree) { + topArmAngleRadians = Math.toRadians(angleDegree); + //addRequirements() used to set subsystem dependencies + addRequirements(ArmSubsystem.getInstance()); + addRequirements(ArmPneumaticsSubsystem.getInstance()); + } + + // called when command is initially scheduled + @Override + public void initialize() { + ArmPneumaticsSubsystem.getInstance().controlTopBrake(false, false); + m_timer.stop(); + m_timer.reset(); + m_timer.start(); + } + + @Override + public void execute() { + ArmSubsystem.getInstance().setTopJointAngle(topArmAngleRadians); + } + + @Override + public void end(boolean interrupted) { + ArmSubsystem.getInstance().stopMotors(); + if (interrupted == false) + { + ArmPneumaticsSubsystem.getInstance().controlTopBrake(true, true); + } + m_timer.stop(); + } + @Override + public boolean isFinished() { + return m_timer.hasElapsed(TIMEOUT_S); + } +} diff --git a/src/main/java/frc/robot/commands/SyncArmEncoders.java b/src/main/java/frc/robot/commands/SyncArmEncoders.java new file mode 100644 index 0000000..13a106d --- /dev/null +++ b/src/main/java/frc/robot/commands/SyncArmEncoders.java @@ -0,0 +1,65 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands; + +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.ArmSubsystem; + +public class SyncArmEncoders extends CommandBase { + int counter; + boolean bSynced; + /** Creates a new SyncArmEncoders. */ + public SyncArmEncoders() { + counter = 0; + bSynced = false; + addRequirements(ArmSubsystem.getInstance()); + // Use addRequirements() here to declare subsystem dependencies. + } + + // Called when the command is initially scheduled. + @Override + public void initialize() {} + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + counter ++; + if (ArmSubsystem.getInstance().areEncodersSynced()==false) { + DriverStation.reportWarning ("Arm encoders are not synced", false); + System.out.println("*****Arm encoders are not synced*****"); + } + else { + DriverStation.reportWarning ("Arm encoders are synced", false); + System.out.println("*****Arm encoders are synced*****"); + bSynced = true; + ArmSubsystem.getInstance().burnFlash(); + } + + + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) {} + + @Override + public boolean runsWhenDisabled() { + return true; + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + if (counter >= 10 || bSynced == true) { + return true; + } + else { + + return false; + } + } +} diff --git a/src/main/java/frc/robot/robotcontainers/PoseidonContainer.java b/src/main/java/frc/robot/robotcontainers/PoseidonContainer.java index 7072d4b..b5f8af3 100644 --- a/src/main/java/frc/robot/robotcontainers/PoseidonContainer.java +++ b/src/main/java/frc/robot/robotcontainers/PoseidonContainer.java @@ -8,6 +8,9 @@ import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Robot; +import frc.robot.commands.SetBottomArm; +import frc.robot.commands.SetTopArm; +import frc.robot.commands.SyncArmEncoders; import frc.robot.commands.ArmPneumaticsCommands.*; import frc.robot.subsystems.GripperSubsystem; @@ -41,6 +44,8 @@ public PoseidonContainer() { * created via the {@link CommandXboxController} or other ways. */ private void configureButtonBindings() { + CommandXboxController driver = new CommandXboxController(0); + CommandXboxController operator = new CommandXboxController (1); /* Driver Controls */ //ArmPneumaticsSubsystem commands @@ -63,7 +68,14 @@ private void configureButtonBindings() { driver.a().onTrue(GripperSubsystem.getInstance().lowPressureCommand()); // B - High Pressure driver.b().onTrue(GripperSubsystem.getInstance().highPressureCommand()); + + /* Operator Controls */ + operator.a().onTrue(new SetBottomArm(90)); + operator.b().onTrue(new SetBottomArm(80)); + operator.x().onTrue(new SetTopArm(10)); + operator.y().onTrue(new SetTopArm(30)); + } /** @@ -75,3 +87,4 @@ public Command getAutonomousCommand() { return new InstantCommand(); } } + diff --git a/src/main/java/frc/robot/subsystems/ArmConfig.java b/src/main/java/frc/robot/subsystems/ArmConfig.java new file mode 100644 index 0000000..aff61fe --- /dev/null +++ b/src/main/java/frc/robot/subsystems/ArmConfig.java @@ -0,0 +1,74 @@ +package frc.robot.subsystems; + +import frc.robot.Config; + +public class ArmConfig { + public static final boolean TOP_SET_INVERTED = true; + public static final boolean BOTTOM_SET_INVERTED = true; + + public static final int CURRENT_LIMIT = 60; + + //soft limit constants for top arm + public static final float top_arm_forward_limit = (float)Math.toRadians(190); //converts degree to radian + public static final float top_arm_reverse_limit = (float)Math.toRadians(7); + public static final boolean TOP_SOFT_LIMIT_ENABLE = true; + + //soft limit constant for bottom arm + public static final float bottom_arm_forward_limit = (float)Math.toRadians(135); + public static final float bottom_arm_reverse_limit = (float)Math.toRadians(40); + public static final boolean BOTTOM_SOFT_LIMIT_ENABLE = true; + + //PID constants + public static final double bottom_arm_kP = 1.4; + public static final double bottom_arm_kI = 0.0003; + public static final double bottom_arm_kD = 0.9; + public static final double bottom_arm_kIz = 0.3; + public static final double bottom_arm_kFF = 0; + public static final double min_output = -1; + public static final double max_output = 1; + + //unfinalized top values + public static final double top_arm_kP = 1.6; + public static final double top_arm_kI = 0.002; + public static final double top_arm_kD = 40; + public static final double top_arm_kIz = 0.3; + public static final double top_arm_kFF = 0; + + + + + + //duty cycle encoders + //public static final int bottom_duty_cycle_channel = 7; + //public static final int top_duty_cycle_channel = 0; + + //arm offsets + //public static final double bottom_arm_offset = 307.800000; + //public static final double top_arm_offset = 0; + + //syncing encoders + public static double ENCODER_SYNCING_TOLERANCE = 0.01; //radians + + //public static final double BOTTOM_NEO_GEAR_RATIO = Config.robotSpecific(62.5,0.0,0.0,0.0); + //public static final double TOP_NEO_GEAR_RATIO = Config.robotSpecific(62.5,0.0,0.0,0.0); + + + //public static final double bottomArmPositionConversionFactor = 2 * Math.PI / BOTTOM_NEO_GEAR_RATIO; + //public static final double bottomArmVelocityConversionFactor = bottomArmPositionConversionFactor / 60.0; + + //public static final double topArmPositionConversionFactor = 2 * Math.PI / BOTTOM_NEO_GEAR_RATIO; + //public static final double topArmVelocityConversionFactor = bottomArmPositionConversionFactor / 60.0; + + + public static final double BOTTOM_MAX_VEL = Math.PI * 3; + public static final double BOTTOM_MAX_ACCEL = Math.PI *3; + + public static final double TOP_MAX_VEL = Math.PI * 0.5; + public static final double TOP_MAX_ACCEL = Math.PI *0.5; + + + + + + +} diff --git a/src/main/java/frc/robot/subsystems/ArmSubsystem.java b/src/main/java/frc/robot/subsystems/ArmSubsystem.java new file mode 100644 index 0000000..4b2724f --- /dev/null +++ b/src/main/java/frc/robot/subsystems/ArmSubsystem.java @@ -0,0 +1,353 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems; + +import com.ctre.phoenix.sensors.AbsoluteSensorRange; +import com.ctre.phoenix.sensors.CANCoder; +import com.ctre.phoenix.sensors.CANCoderConfiguration; +import com.ctre.phoenix.sensors.SensorInitializationStrategy; +import com.ctre.phoenix.sensors.SensorTimeBase; +import com.revrobotics.CANSparkMax; +import com.revrobotics.CANSparkMax.ControlType; +import com.revrobotics.RelativeEncoder; +import com.revrobotics.SparkMaxAbsoluteEncoder; +import com.revrobotics.SparkMaxPIDController; +import com.revrobotics.CANSparkMax.IdleMode; +import com.revrobotics.CANSparkMax.SoftLimitDirection; +import com.revrobotics.CANSparkMaxLowLevel.MotorType; +import com.revrobotics.CANSparkMaxLowLevel.PeriodicFrame; +import com.revrobotics.SparkMaxAbsoluteEncoder.Type; + +import frc.robot.Config; +import frc.robot.ErrorCheck; +import frc.robot.ProfiledPIDFFController; +import frc.robot.SubsystemChecker; +import frc.robot.SubsystemChecker.SubsystemType; +import edu.wpi.first.networktables.DoubleEntry; +import edu.wpi.first.networktables.DoublePublisher; +import edu.wpi.first.networktables.DoubleSubscriber; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.networktables.PubSubOption; +import edu.wpi.first.networktables.Topic; +import edu.wpi.first.wpilibj.DoubleSolenoid; +import edu.wpi.first.wpilibj.DutyCycleEncoder; +import edu.wpi.first.wpilibj.PneumaticsModuleType; +import edu.wpi.first.wpilibj.DoubleSolenoid.Value; +import edu.wpi.first.wpilibj2.command.SubsystemBase; + +public class ArmSubsystem extends SubsystemBase { + private static ArmSubsystem instance = null; //static object that contains all movement controls + + private static final MotorType motorType = MotorType.kBrushless; //defines brushless motortype + public final CANSparkMax m_bottomArm; //bottom SparkMax motor controller + public final CANSparkMax m_topArm; //bottom SparkMax motor controller + + + //network table entry + private final String m_tuningTableBottom = "Arm/BottomArmTuning"; + private final String m_dataTableBottom = "Arm/BottomArmData"; + private final String m_tuningTableTop = "Arm/TopArmTuning"; + private final String m_dataTableTop = "Arm/TopArmData"; + + //network table entries for bottom arm + private DoubleEntry m_bottomArmPSubs; + private DoubleEntry m_bottomArmISubs; + private DoubleEntry m_bottomArmDSubs; + private DoubleEntry m_bottomArmIzSubs; + private DoubleEntry m_bottomArmFFSubs; + private DoublePublisher m_bottomArmSetpointPub; + private DoublePublisher m_bottomArmVelPub; + private DoubleEntry m_bottomArmMomentToVoltage; + private DoublePublisher m_bottomArmFFTestingVolts; + private DoubleEntry m_bottomArmOffset; + private DoublePublisher m_bottomTargetAngle; + private DoublePublisher m_bottomArmPosPub; + + //network tables entries for top arm + private DoubleEntry m_topArmPSubs; + private DoubleEntry m_topArmISubs; + private DoubleEntry m_topArmDSubs; + private DoubleEntry m_topArmIzSubs; + private DoubleEntry m_topArmFFSubs; + private DoublePublisher m_topArmSetpointPub; + private DoublePublisher m_topArmVelPub; + private DoubleEntry m_topArmMomentToVoltage; + private DoublePublisher m_topArmFFTestingVolts; + private DoubleEntry m_topArmOffset; + private DoublePublisher m_topTargetAngle; + private DoublePublisher m_topArmPosPub; + + //for bottom arm ff + private DoubleSubscriber momentToVoltageConversion; + private double m_bottomVoltageConversion; + //for top arm ff + private double m_topVoltageConversion; + + + //spark max absolute encoder + SparkMaxAbsoluteEncoder m_bottomAbsEncoder; + SparkMaxAbsoluteEncoder m_topAbsEncoder; + + //embedded relative encoder + //private RelativeEncoder m_bottomEncoder; + public SparkMaxPIDController m_pidControllerBottomArm; + public SparkMaxPIDController m_pidControllerTopArm; + + ProfiledPIDFFController m_profiledFFController = new ProfiledPIDFFController(); + + + public static ArmSubsystem getInstance() { //gets arm subsystem object to control movement + if (instance == null) { + SubsystemChecker.subsystemConstructed(SubsystemType.ArmSubsystem); + instance = new ArmSubsystem(); + } + return instance; + } + + /** Creates a new ArmSubsystem. */ + public ArmSubsystem() { + + m_bottomArm = new CANSparkMax(Config.CANID.BOTTOM_ARM_SPARK_CAN_ID, motorType); //creates SparkMax motor controller for bottom joint + ErrorCheck.errREV(m_bottomArm.restoreFactoryDefaults()); + ErrorCheck.errREV(m_bottomArm.setSmartCurrentLimit(ArmConfig.CURRENT_LIMIT)); + m_bottomArm.setInverted(ArmConfig.BOTTOM_SET_INVERTED); //sets movement direction + ErrorCheck.errREV(m_bottomArm.setIdleMode(IdleMode.kBrake)); //sets brakes when there is no motion + + ErrorCheck.errREV(m_bottomArm.setSoftLimit(SoftLimitDirection.kForward, ArmConfig.bottom_arm_forward_limit)); + ErrorCheck.errREV(m_bottomArm.setSoftLimit(SoftLimitDirection.kReverse, ArmConfig.bottom_arm_reverse_limit)); + ErrorCheck.errREV(m_bottomArm.enableSoftLimit(SoftLimitDirection.kForward, ArmConfig.BOTTOM_SOFT_LIMIT_ENABLE)); + ErrorCheck.errREV(m_bottomArm.enableSoftLimit(SoftLimitDirection.kReverse, ArmConfig.BOTTOM_SOFT_LIMIT_ENABLE)); + + m_topArm = new CANSparkMax(Config.CANID.TOP_ARM_SPARK_CAN_ID, motorType); + ErrorCheck.errREV(m_topArm.restoreFactoryDefaults()); + ErrorCheck.errREV(m_topArm.setSmartCurrentLimit(ArmConfig.CURRENT_LIMIT)); + m_topArm.setInverted(ArmConfig.TOP_SET_INVERTED); + ErrorCheck.errREV(m_topArm.setIdleMode(IdleMode.kBrake)); + + ErrorCheck.errREV(m_topArm.setSoftLimit(SoftLimitDirection.kForward, ArmConfig.top_arm_forward_limit)); + ErrorCheck.errREV(m_topArm.setSoftLimit(SoftLimitDirection.kReverse, ArmConfig.top_arm_reverse_limit)); + ErrorCheck.errREV(m_topArm.enableSoftLimit(SoftLimitDirection.kForward, ArmConfig.TOP_SOFT_LIMIT_ENABLE)); + ErrorCheck.errREV(m_topArm.enableSoftLimit(SoftLimitDirection.kReverse, ArmConfig.TOP_SOFT_LIMIT_ENABLE)); + + m_topArm.setPeriodicFramePeriod(PeriodicFrame.kStatus5, 20); + m_topArm.setPeriodicFramePeriod(PeriodicFrame.kStatus6, 20); + + m_bottomArm.setPeriodicFramePeriod(PeriodicFrame.kStatus5, 20); + m_bottomArm.setPeriodicFramePeriod(PeriodicFrame.kStatus6, 20); + + + //unit: radius + m_bottomAbsEncoder = m_bottomArm.getAbsoluteEncoder(Type.kDutyCycle); + m_bottomAbsEncoder.setInverted(true); + m_bottomAbsEncoder.setPositionConversionFactor(2*Math.PI); + m_bottomAbsEncoder.setVelocityConversionFactor(2*Math.PI/60.0); + m_bottomAbsEncoder.setZeroOffset(Math.toRadians(52)); + + m_topAbsEncoder = m_topArm.getAbsoluteEncoder(Type.kDutyCycle); + m_topAbsEncoder.setInverted(false); + m_topAbsEncoder.setPositionConversionFactor(2*Math.PI); + m_topAbsEncoder.setVelocityConversionFactor(2*Math.PI/60.0); + m_topAbsEncoder.setZeroOffset(Math.toRadians(286)); + + m_pidControllerBottomArm = m_bottomArm.getPIDController(); + m_pidControllerBottomArm.setFeedbackDevice(m_bottomAbsEncoder); + + m_pidControllerTopArm = m_topArm.getPIDController(); + m_pidControllerTopArm.setFeedbackDevice(m_topAbsEncoder); + + NetworkTable topArmTuningTable = NetworkTableInstance.getDefault().getTable(m_tuningTableTop); + m_topArmPSubs = topArmTuningTable.getDoubleTopic("P").getEntry(ArmConfig.top_arm_kP, PubSubOption.periodic(0.02)); + m_topArmISubs = topArmTuningTable.getDoubleTopic("I").getEntry(ArmConfig.top_arm_kI); + m_topArmDSubs = topArmTuningTable.getDoubleTopic("D").getEntry(ArmConfig.top_arm_kD); + m_topArmIzSubs = topArmTuningTable.getDoubleTopic("IZone").getEntry(ArmConfig.top_arm_kIz); + m_topArmFFSubs = topArmTuningTable.getDoubleTopic("FF").getEntry(ArmConfig.top_arm_kFF); + //m_topArmOffset = topArmTuningTable.getDoubleTopic("Offset").getEntry(ArmConfig.top_arm_offset); + momentToVoltageConversion = topArmTuningTable.getDoubleTopic("VoltageConversion").subscribe(m_topVoltageConversion); + + NetworkTable bottomArmTuningTable = NetworkTableInstance.getDefault().getTable(m_tuningTableBottom); + m_bottomArmPSubs = bottomArmTuningTable.getDoubleTopic("P").getEntry(ArmConfig.bottom_arm_kP); + m_bottomArmISubs = bottomArmTuningTable.getDoubleTopic("I").getEntry(ArmConfig.bottom_arm_kI); + m_bottomArmDSubs = bottomArmTuningTable.getDoubleTopic("D").getEntry(ArmConfig.bottom_arm_kD); + m_bottomArmIzSubs = bottomArmTuningTable.getDoubleTopic("IZone").getEntry(ArmConfig.bottom_arm_kIz); + m_bottomArmFFSubs = bottomArmTuningTable.getDoubleTopic("FF").getEntry(ArmConfig.bottom_arm_kFF); + //m_bottomArmOffset = bottomArmTuningTable.getDoubleTopic("Offset").getEntry(ArmConfig.bottom_arm_offset); + momentToVoltageConversion = bottomArmTuningTable.getDoubleTopic("VoltageConversion").subscribe(m_bottomVoltageConversion); + + m_bottomArmFFSubs.accept(ArmConfig.bottom_arm_kFF); + m_bottomArmPSubs.accept(ArmConfig.bottom_arm_kP); + m_bottomArmISubs.accept(ArmConfig.bottom_arm_kI); + m_bottomArmDSubs.accept(ArmConfig.bottom_arm_kD); + m_bottomArmIzSubs.accept(ArmConfig.bottom_arm_kIz); + //m_bottomArmOffset.accept(ArmConfig.bottom_arm_offset); + + m_topArmFFSubs.accept(ArmConfig.top_arm_kFF); + m_topArmPSubs.accept(ArmConfig.top_arm_kP); + m_topArmISubs.accept(ArmConfig.top_arm_kI); + m_topArmDSubs.accept(ArmConfig.top_arm_kD); + m_topArmIzSubs.accept(ArmConfig.top_arm_kIz); + + //m_bottomArmOffset = bottomArmTuningTable.getDoubleTopic("Offset").getEntry(ArmConfig.bottom_arm_offset); + //m_bottomArmOffset.accept(ArmConfig.bottom_arm_offset); + + NetworkTable bottomArmDataTable = NetworkTableInstance.getDefault().getTable(m_dataTableBottom); + NetworkTable topArmDataTable = NetworkTableInstance.getDefault().getTable(m_dataTableTop); + + + m_bottomArmPosPub = bottomArmDataTable.getDoubleTopic("MeasuredAngle").publish(PubSubOption.periodic(0.02)); + m_bottomTargetAngle = bottomArmDataTable.getDoubleTopic("TargetAngle").publish(PubSubOption.periodic(0.02)); + m_bottomArmVelPub = bottomArmDataTable.getDoubleTopic("Vel").publish(PubSubOption.periodic(0.02)); + + m_topArmPosPub = topArmDataTable.getDoubleTopic("MeasuredAngle").publish(PubSubOption.periodic(0.02)); + m_topTargetAngle = topArmDataTable.getDoubleTopic("TargetAngle").publish(PubSubOption.periodic(0.02)); + m_topArmVelPub = topArmDataTable.getDoubleTopic("Vel").publish(PubSubOption.periodic(0.02)); + + + ErrorCheck.errREV(m_pidControllerBottomArm.setFF(m_bottomArmFFSubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setP(m_bottomArmPSubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setI(m_bottomArmISubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setD(m_bottomArmDSubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setIZone(m_bottomArmIzSubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setOutputRange(ArmConfig.min_output, ArmConfig.max_output)); + + ErrorCheck.errREV(m_pidControllerTopArm.setFF(m_topArmFFSubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setP(m_topArmPSubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setI(m_topArmISubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setD(m_topArmDSubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setIZone(m_topArmIzSubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setOutputRange(ArmConfig.min_output, ArmConfig.max_output)); + + + //to do: could be moved to another spot + updatePIDSettings(); + //updateFromAbsoluteBottom(); + } + + public void updatePIDSettings() { + ErrorCheck.errREV(m_pidControllerBottomArm.setFF(m_bottomArmFFSubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setP(m_bottomArmPSubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setI(m_bottomArmISubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setD(m_bottomArmDSubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setIZone(m_bottomArmIzSubs.get())); + ErrorCheck.errREV(m_pidControllerBottomArm.setOutputRange(ArmConfig.min_output, ArmConfig.max_output)); + + ErrorCheck.errREV(m_pidControllerTopArm.setFF(m_topArmFFSubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setP(m_topArmPSubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setI(m_topArmISubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setD(m_topArmDSubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setIZone(m_topArmIzSubs.get())); + ErrorCheck.errREV(m_pidControllerTopArm.setOutputRange(ArmConfig.min_output, ArmConfig.max_output)); + + } + + + @Override + public void periodic() { + m_bottomArmPosPub.accept(Math.toDegrees(m_bottomAbsEncoder.getPosition())); + m_bottomArmVelPub.accept(m_bottomAbsEncoder.getVelocity()); + m_bottomTargetAngle.accept(Math.toDegrees(getAbsoluteBottom())); + + m_topArmPosPub.accept(Math.toDegrees(m_topAbsEncoder.getPosition())); + m_topArmVelPub.accept(m_topAbsEncoder.getVelocity()); + // This method will be called once per scheduler run + } + + //input angle_bottom in radians + public void setBottomJointAngle(double angle_bottom) { + if (angle_bottomMath.toRadians(95)) { + angle_bottom = Math.toRadians(95); + } + //setReference angle is in radians) + //todo: tune FF + m_pidControllerBottomArm.setReference((angle_bottom), ControlType.kPosition, 0,0.1); + } + + public void setTopJointAngle(double angle_top) { + if (angle_topMath.toRadians(35)) { + angle_top = Math.toRadians(10); + } + //setReference angle is in radians) + //todo: tune FF + double targetPos = m_profiledFFController.getNextProfiledPIDPos(getTopPosition(), angle_top); + m_pidControllerTopArm.setReference((targetPos), ControlType.kPosition, 0, calculateFFTop()); + m_topTargetAngle.accept(Math.toDegrees(targetPos)); + System.out.println(targetPos); + + } + + /*public void controlBottomArmBrake( boolean bBrakeOn) { + if (bBrakeOn == true) { + //set brake on the arm + brakeSolenoidLow.set(Value.kForward); + } + else { + brakeSolenoidLow.set(Value.kReverse); + } + } + */ + + //return radius + public double getBottomPosition() { + return m_bottomAbsEncoder.getPosition(); + } + public double getTopPosition() { + return m_topAbsEncoder.getPosition(); + } + + public double getAbsoluteBottom() { + //getAbsolutePosition() return in [0,1] + //return Math.toRadians(m_bottomDutyCycleEncoder.getAbsolutePosition() * -360 + m_bottomArmOffset.get()); + //double absPosition = m_bottomAbsEncoder.getPosition(); + //double adjAbsPosition = absPosition-((int) absPosition/360)*360.0; + //System.out.println("Get abs position(degree) " + absPosition); + //System.out.println("adjusted abs position " + adjAbsPosition); + return m_bottomAbsEncoder.getPosition(); //+ m_bottomArmOffset.get()); + } + + public double getAbsoluteTop() { + return m_topAbsEncoder.getPosition(); + } + + //public void updateFromAbsoluteBottom() { + //todo: check REV system error + //ErrorCheck.errREV(m_bottomEncoder.setPosition(getAbsoluteBottom())); + //} + + public boolean areEncodersSynced() { + System.out.println("*****areEncodersSynced*****"); + boolean syncResult; + //set sparkmax encoder position + //updateFromAbsoluteBottom(); + System.out.println("getAbsoluteBottom " + getAbsoluteBottom()); + System.out.println("getBottomPosition " + getBottomPosition()); + syncResult = Math.abs(getAbsoluteBottom() - getBottomPosition()) < ArmConfig.ENCODER_SYNCING_TOLERANCE; + System.out.println("******SyncIteration****** " + "******Result******" + syncResult); + + System.out.println("getAbsoluteTop " + getAbsoluteTop()); + System.out.println("getTopPosition " + getTopPosition()); + syncResult = Math.abs(getAbsoluteTop() - getTopPosition()) < ArmConfig.ENCODER_SYNCING_TOLERANCE; + System.out.println("******SyncIteration****** " + "******Result******" + syncResult); + + return syncResult; + } + public void stopMotors() { + m_bottomArm.stopMotor(); + m_topArm.stopMotor(); + } + public void burnFlash() { + ErrorCheck.errREV(m_bottomArm.burnFlash()); + ErrorCheck.errREV(m_topArm.burnFlash()); + } + private double calculateFFTop() { + double enc2AtHorizontal = getTopPosition() - (Math.PI - getBottomPosition()); + double voltsAtHorizontal; + voltsAtHorizontal = 2.0; + //System.out.println("top position " + getTopPosition()); + //System.out.println("bottom position " + getBottomPosition()); + //System.out.println("calculated position " + enc2AtHorizontal); + System.out.println("return voltage " + voltsAtHorizontal * Math.cos(enc2AtHorizontal)); + return voltsAtHorizontal * Math.cos(enc2AtHorizontal); + } +} diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib.json index 8e61586..e1f6e52 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib.json @@ -1,8 +1,9 @@ { "fileName": "PathplannerLib.json", "name": "PathplannerLib", - "version": "2023.4.4", + "version": "2024.0.0-beta-5.1", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", + "frcYear": "2024", "mavenUrls": [ "https://3015rangerrobotics.github.io/pathplannerlib/repo" ], @@ -11,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2023.4.4" + "version": "2024.0.0-beta-5.1" } ], "jniDependencies": [], @@ -19,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2023.4.4", + "version": "2024.0.0-beta-5.1", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -28,7 +29,9 @@ "windowsx86-64", "linuxx86-64", "osxuniversal", - "linuxathena" + "linuxathena", + "linuxarm32", + "linuxarm64" ] } ] diff --git a/vendordeps/Phoenix5.json b/vendordeps/Phoenix5.json new file mode 100644 index 0000000..41fa3f1 --- /dev/null +++ b/vendordeps/Phoenix5.json @@ -0,0 +1,151 @@ +{ + "fileName": "Phoenix5.json", + "name": "CTRE-Phoenix (v5)", + "version": "5.32.0-beta-2", + "frcYear": 2024, + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2024-beta-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-beta-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.32.0-beta-2" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.32.0-beta-2" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.32.0-beta-2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.32.0-beta-2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.32.0-beta-2", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.32.0-beta-2", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.32.0-beta-2", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.32.0-beta-2", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.32.0-beta-2", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.32.0-beta-2", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/vendordeps/Phoenix6.json b/vendordeps/Phoenix6.json new file mode 100644 index 0000000..c64ffa2 --- /dev/null +++ b/vendordeps/Phoenix6.json @@ -0,0 +1,339 @@ +{ + "fileName": "Phoenix6.json", + "name": "CTRE-Phoenix (v6)", + "version": "24.0.0-beta-4", + "frcYear": 2024, + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-beta-latest.json", + "conflictsWith": [ + { + "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a", + "errorMessage": "The combined Phoenix-6-And-5 vendordep is no longer supported. Please remove the vendordep and instead add both the latest Phoenix 6 vendordep and Phoenix 5 vendordep.", + "offlineFileName": "Phoenix6And5.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "24.0.0-beta-4" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "24.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "24.0.0-beta-4", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "24.0.0-beta-4", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "24.0.0-beta-4", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "24.0.0-beta-4", + "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": "24.0.0-beta-4", + "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": "24.0.0-beta-4", + "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": "24.0.0-beta-4", + "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": "24.0.0-beta-4", + "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": "24.0.0-beta-4", + "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": "24.0.0-beta-4", + "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": "24.0.0-beta-4", + "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": "24.0.0-beta-4", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index f2d0b7d..7eb3755 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,24 +1,25 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2023.1.3", + "version": "2024.0.0", + "frcYear": "2024", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ "https://maven.revrobotics.com/" ], - "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json", + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json", "javaDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2023.1.3" + "version": "2024.0.0" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2023.1.3", + "version": "2024.0.0", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -36,7 +37,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2023.1.3", + "version": "2024.0.0", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -54,7 +55,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2023.1.3", + "version": "2024.0.0", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json index bd535bf..67bf389 100644 --- a/vendordeps/WPILibNewCommands.json +++ b/vendordeps/WPILibNewCommands.json @@ -3,6 +3,7 @@ "name": "WPILib-New-Commands", "version": "1.0.0", "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", + "frcYear": "2024", "mavenUrls": [], "jsonUrl": "", "javaDependencies": [ diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json index dad3105..c940b75 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib.json @@ -1,8 +1,9 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2023.4.2", - "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004 ", + "version": "v2024.1.1-beta-3.2", + "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", + "frcYear": "2024", "mavenUrls": [ "https://maven.photonvision.org/repository/internal", "https://maven.photonvision.org/repository/snapshots" @@ -13,7 +14,7 @@ { "groupId": "org.photonvision", "artifactId": "PhotonLib-cpp", - "version": "v2023.4.2", + "version": "v2024.1.1-beta-3.2", "libName": "Photon", "headerClassifier": "headers", "sharedLibrary": true, @@ -30,12 +31,12 @@ { "groupId": "org.photonvision", "artifactId": "PhotonLib-java", - "version": "v2023.4.2" + "version": "v2024.1.1-beta-3.2" }, { "groupId": "org.photonvision", "artifactId": "PhotonTargeting-java", - "version": "v2023.4.2" + "version": "v2024.1.1-beta-3.2" } ] } \ No newline at end of file