mirror of
https://github.com/Team4388/2026KPopRobotHunters.git
synced 2026-06-08 16:28:05 -06:00
Sparkmax for arm motor
This commit is contained in:
@@ -98,9 +98,9 @@ public class RobotMap {
|
|||||||
TalonFX indexer = new TalonFX(ShooterConstants.INDEXER_ID.id, Constants.CANIVORE_CANBUS);
|
TalonFX indexer = new TalonFX(ShooterConstants.INDEXER_ID.id, Constants.CANIVORE_CANBUS);
|
||||||
|
|
||||||
//Configure Intake 20,21
|
//Configure Intake 20,21
|
||||||
TalonFX arm = new TalonFX(IntakeConstants.ARM_ID.id, Constants.CANIVORE_CANBUS);
|
SparkMax arm = new SparkMax(IntakeConstants.ARM_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless);
|
||||||
SparkMax roller = new SparkMax(IntakeConstants.ROLLER_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless);
|
SparkMax roller = new SparkMax(IntakeConstants.ROLLER_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless);
|
||||||
DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL);
|
// DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL);
|
||||||
// DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH);
|
// DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH);
|
||||||
// DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH);
|
// DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH);
|
||||||
// DigitalInput IRIntakeBeam = new DigitalInput(ElevatorConstants.INTAKE_LIMIT_SWITCH);
|
// DigitalInput IRIntakeBeam = new DigitalInput(ElevatorConstants.INTAKE_LIMIT_SWITCH);
|
||||||
@@ -109,7 +109,7 @@ public class RobotMap {
|
|||||||
// shooterIO = new ShooterIO() {};
|
// shooterIO = new ShooterIO() {};
|
||||||
shooterIO = new ShooterReal(shooter1, shooter2, indexer);
|
shooterIO = new ShooterReal(shooter1, shooter2, indexer);
|
||||||
|
|
||||||
intakeIO = new IntakeReal(armLimitSwitch, arm, roller);
|
intakeIO = new IntakeReal(arm, roller);
|
||||||
|
|
||||||
// Fault
|
// Fault
|
||||||
FaultPidgeon2.addDevice(swerveDrivetrainReal.getPigeon2(), "Gyro");
|
FaultPidgeon2.addDevice(swerveDrivetrainReal.getPigeon2(), "Gyro");
|
||||||
@@ -118,7 +118,7 @@ public class RobotMap {
|
|||||||
FaultTalonFX.addDevice(shooter1, "Shooter1");
|
FaultTalonFX.addDevice(shooter1, "Shooter1");
|
||||||
FaultTalonFX.addDevice(shooter2, "Shooter2");
|
FaultTalonFX.addDevice(shooter2, "Shooter2");
|
||||||
FaultTalonFX.addDevice(indexer, "Indexer");
|
FaultTalonFX.addDevice(indexer, "Indexer");
|
||||||
FaultTalonFX.addDevice(arm, "Arm");
|
// FaultTalonFX.addDevice(arm, "Arm");
|
||||||
// FaultTalonFX.addDevice(roller, "Roller");
|
// FaultTalonFX.addDevice(roller, "Roller");
|
||||||
|
|
||||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive");
|
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive");
|
||||||
|
|||||||
@@ -5,14 +5,14 @@ package frc4388.robot.constants;
|
|||||||
*/
|
*/
|
||||||
public final class BuildConstants {
|
public final class BuildConstants {
|
||||||
public static final String MAVEN_GROUP = "";
|
public static final String MAVEN_GROUP = "";
|
||||||
public static final String MAVEN_NAME = "2026KPopRobotHunters-new";
|
public static final String MAVEN_NAME = "2026KPopRobotHunters";
|
||||||
public static final String VERSION = "unspecified";
|
public static final String VERSION = "unspecified";
|
||||||
public static final int GIT_REVISION = 184;
|
public static final int GIT_REVISION = 185;
|
||||||
public static final String GIT_SHA = "c6b0d29acdb24728ed566b25d6434a45fbd963c7";
|
public static final String GIT_SHA = "7eba3d8faa208df9222599c53db1e11da82d7a96";
|
||||||
public static final String GIT_DATE = "2026-03-25 11:15:46 MDT";
|
public static final String GIT_DATE = "2026-03-25 11:39:55 MDT";
|
||||||
public static final String GIT_BRANCH = "New-Intake";
|
public static final String GIT_BRANCH = "New-Intake";
|
||||||
public static final String BUILD_DATE = "2026-03-25 11:17:58 MDT";
|
public static final String BUILD_DATE = "2026-03-28 09:26:32 MDT";
|
||||||
public static final long BUILD_UNIX_TIME = 1774459078868L;
|
public static final long BUILD_UNIX_TIME = 1774711592752L;
|
||||||
public static final int DIRTY = 1;
|
public static final int DIRTY = 1;
|
||||||
|
|
||||||
private BuildConstants(){}
|
private BuildConstants(){}
|
||||||
|
|||||||
@@ -96,19 +96,19 @@ public class Intake extends SubsystemBase {
|
|||||||
|
|
||||||
switch (mode) {
|
switch (mode) {
|
||||||
case Extended:
|
case Extended:
|
||||||
io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_EXTENDED.get()));
|
// io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_EXTENDED.get()));
|
||||||
io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get());
|
// io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get());
|
||||||
break;
|
break;
|
||||||
case Retracted:
|
case Retracted:
|
||||||
io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_RETRACTED.get()));
|
// io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_LIMIT_RETRACTED.get()));
|
||||||
io.setRollerOutput(state, 0);
|
// io.setRollerOutput(state, 0);
|
||||||
break;
|
break;
|
||||||
case Extending:
|
case Extending:
|
||||||
io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get()));
|
io.armOutput(IntakeConstants.ARM_EXTEND_PERCENT_OUTPUT.get());
|
||||||
io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get());
|
io.setRollerOutput(state, IntakeConstants.ROLLER_PERCENT_OUTPUT.get());
|
||||||
break;
|
break;
|
||||||
case Retracting:
|
case Retracting:
|
||||||
io.setArmAngle(state, Rotations.of(IntakeConstants.ARM_RETRACT_PERCENT_OUTPUT.get()));
|
io.armOutput(IntakeConstants.ARM_RETRACT_PERCENT_OUTPUT.get());
|
||||||
io.setRollerOutput(state, 0);
|
io.setRollerOutput(state, 0);
|
||||||
break;
|
break;
|
||||||
case Bouncing:
|
case Bouncing:
|
||||||
|
|||||||
@@ -1,16 +1,10 @@
|
|||||||
package frc4388.robot.subsystems.intake;
|
package frc4388.robot.subsystems.intake;
|
||||||
|
|
||||||
import static edu.wpi.first.units.Units.Amps;
|
import com.revrobotics.spark.FeedbackSensor;
|
||||||
import static edu.wpi.first.units.Units.RotationsPerSecond;
|
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||||
|
import com.revrobotics.spark.config.LimitSwitchConfig.Behavior;
|
||||||
|
import com.revrobotics.spark.config.LimitSwitchConfig.Type;
|
||||||
|
|
||||||
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
|
|
||||||
import com.ctre.phoenix6.configs.MotorOutputConfigs;
|
|
||||||
import com.ctre.phoenix6.configs.Slot0Configs;
|
|
||||||
import com.ctre.phoenix6.configs.TalonFXConfiguration;
|
|
||||||
import com.ctre.phoenix6.signals.NeutralModeValue;
|
|
||||||
|
|
||||||
import edu.wpi.first.units.measure.AngularVelocity;
|
|
||||||
import edu.wpi.first.units.measure.Current;
|
|
||||||
import frc4388.utility.configurable.ConfigurableDouble;
|
import frc4388.utility.configurable.ConfigurableDouble;
|
||||||
import frc4388.utility.status.CanDevice;
|
import frc4388.utility.status.CanDevice;
|
||||||
|
|
||||||
@@ -33,7 +27,7 @@ public class IntakeConstants {
|
|||||||
|
|
||||||
public static final CanDevice ARM_ID = new CanDevice("ARM", 20);
|
public static final CanDevice ARM_ID = new CanDevice("ARM", 20);
|
||||||
public static final CanDevice ROLLER_ID = new CanDevice("INTAKE_ROLLER", 21);
|
public static final CanDevice ROLLER_ID = new CanDevice("INTAKE_ROLLER", 21);
|
||||||
public static final int ARM_LIMIT_SWITCH_CHANNEL = 9;
|
// public static final int ARM_LIMIT_SWITCH_CHANNEL = 9;
|
||||||
|
|
||||||
// Limits
|
// Limits
|
||||||
|
|
||||||
@@ -46,7 +40,7 @@ public class IntakeConstants {
|
|||||||
// public static final Angle ARM_LIMIT_UPPER = Degrees.of(-90);
|
// public static final Angle ARM_LIMIT_UPPER = Degrees.of(-90);
|
||||||
|
|
||||||
public static final ConfigurableDouble ARM_LIMIT_RETRACTED = new ConfigurableDouble("Arm angle retracted", 0.1);
|
public static final ConfigurableDouble ARM_LIMIT_RETRACTED = new ConfigurableDouble("Arm angle retracted", 0.1);
|
||||||
public static final ConfigurableDouble ARM_LIMIT_EXTENDED = new ConfigurableDouble("Arm angle extended", 0.33);
|
public static final ConfigurableDouble ARM_ssLIMIT_EXTENDED = new ConfigurableDouble("Arm angle extended", 0.33);
|
||||||
public static final ConfigurableDouble ARM_EXTEND_PERCENT_OUTPUT = new ConfigurableDouble("Arm extend % output", 0.4);
|
public static final ConfigurableDouble ARM_EXTEND_PERCENT_OUTPUT = new ConfigurableDouble("Arm extend % output", 0.4);
|
||||||
public static final ConfigurableDouble ARM_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Arm retract % output", -0.4);
|
public static final ConfigurableDouble ARM_RETRACT_PERCENT_OUTPUT = new ConfigurableDouble("Arm retract % output", -0.4);
|
||||||
public static final ConfigurableDouble ROLLER_PERCENT_OUTPUT = new ConfigurableDouble("Roller Percent Output", .70);
|
public static final ConfigurableDouble ROLLER_PERCENT_OUTPUT = new ConfigurableDouble("Roller Percent Output", .70);
|
||||||
@@ -56,16 +50,16 @@ public class IntakeConstants {
|
|||||||
// public static final AngularVelocity ROLLER_STOP = RotationsPerSecond.of(0.0);
|
// public static final AngularVelocity ROLLER_STOP = RotationsPerSecond.of(0.0);
|
||||||
|
|
||||||
|
|
||||||
public static final Slot0Configs ARM_PID = new Slot0Configs()
|
// public static final Slot0Configs ARM_PID = new Slot0Configs()
|
||||||
.withKP(0.08)
|
// .withKP(0.08)
|
||||||
.withKI(0.0)
|
// .withKI(0.0)
|
||||||
.withKD(0.05);
|
// .withKD(0.05);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
public static ConfigurableDouble arm_kP = new ConfigurableDouble("ARM KP", 0.08);
|
// public static ConfigurableDouble arm_kP = new ConfigurableDouble("ARM KP", 0.08);
|
||||||
public static ConfigurableDouble arm_kI = new ConfigurableDouble("ARM KI", 0);
|
// public static ConfigurableDouble arm_kI = new ConfigurableDouble("ARM KI", 0);
|
||||||
public static ConfigurableDouble arm_kD = new ConfigurableDouble("ARM KD", 0.05);
|
// public static ConfigurableDouble arm_kD = new ConfigurableDouble("ARM KD", 0.05);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@@ -75,25 +69,37 @@ public class IntakeConstants {
|
|||||||
// public static final Angle PITCH_LIMIT_LOWER = Degrees.of(0);
|
// public static final Angle PITCH_LIMIT_LOWER = Degrees.of(0);
|
||||||
|
|
||||||
// Motor configs
|
// Motor configs
|
||||||
public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration()
|
|
||||||
.withCurrentLimits(
|
|
||||||
new CurrentLimitsConfigs()
|
|
||||||
.withStatorCurrentLimit(15) // TODO: tune???
|
|
||||||
.withStatorCurrentLimitEnable(true)
|
|
||||||
).withMotorOutput(
|
|
||||||
new MotorOutputConfigs()
|
|
||||||
.withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate
|
|
||||||
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
|
||||||
);
|
|
||||||
|
|
||||||
public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration()
|
public static final SparkMaxConfig ARM_MOTOR_CONFIG = new SparkMaxConfig();
|
||||||
.withCurrentLimits(
|
public static final SparkMaxConfig ROLELR_MOTOR_CONFIG = new SparkMaxConfig();
|
||||||
new CurrentLimitsConfigs()
|
|
||||||
.withStatorCurrentLimit(40) // TODO: tune???
|
static {
|
||||||
.withStatorCurrentLimitEnable(true)
|
ARM_MOTOR_CONFIG.limitSwitch
|
||||||
).withMotorOutput(
|
.reverseLimitSwitchType(Type.kNormallyClosed)
|
||||||
new MotorOutputConfigs()
|
.limitSwitchPositionSensor(FeedbackSensor.kPrimaryEncoder)
|
||||||
.withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny
|
.forwardLimitSwitchPosition(0)
|
||||||
.withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
.forwardLimitSwitchTriggerBehavior(Behavior.kStopMovingMotorAndSetPosition);
|
||||||
);
|
}
|
||||||
|
|
||||||
|
// public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration()
|
||||||
|
// .withCurrentLimits(
|
||||||
|
// new CurrentLimitsConfigs()
|
||||||
|
// .withStatorCurrentLimit(15) // TODO: tune???
|
||||||
|
// .withStatorCurrentLimitEnable(true)
|
||||||
|
// ).withMotorOutput(
|
||||||
|
// new MotorOutputConfigs()
|
||||||
|
// .withNeutralMode(NeutralModeValue.Brake) // Must be break because this has to be accurate
|
||||||
|
// .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
||||||
|
// );
|
||||||
|
|
||||||
|
// public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration()
|
||||||
|
// .withCurrentLimits(
|
||||||
|
// new CurrentLimitsConfigs()
|
||||||
|
// .withStatorCurrentLimit(40) // TODO: tune???
|
||||||
|
// .withStatorCurrentLimitEnable(true)
|
||||||
|
// ).withMotorOutput(
|
||||||
|
// new MotorOutputConfigs()
|
||||||
|
// .withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny
|
||||||
|
// .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means
|
||||||
|
// );
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -23,7 +23,7 @@ public interface IntakeIO {
|
|||||||
Current armMotorCurrent = Amps.of(0);
|
Current armMotorCurrent = Amps.of(0);
|
||||||
|
|
||||||
AngularVelocity armMotorVelocity = RotationsPerSecond.of(0);
|
AngularVelocity armMotorVelocity = RotationsPerSecond.of(0);
|
||||||
AngularAcceleration armMotorAcceleration = RotationsPerSecondPerSecond.of(0);
|
// AngularAcceleration armMotorAcceleration = RotationsPerSecondPerSecond.of(0);
|
||||||
|
|
||||||
// Angle shooterPitch = Rotations.of(0);
|
// Angle shooterPitch = Rotations.of(0);
|
||||||
// Angle shooterTargetPitch = Rotations.of(0);
|
// Angle shooterTargetPitch = Rotations.of(0);
|
||||||
|
|||||||
@@ -1,7 +1,10 @@
|
|||||||
package frc4388.robot.subsystems.intake;
|
package frc4388.robot.subsystems.intake;
|
||||||
|
|
||||||
import static edu.wpi.first.units.Units.Amps;
|
import static edu.wpi.first.units.Units.Amps;
|
||||||
|
import static edu.wpi.first.units.Units.Rotation;
|
||||||
import static edu.wpi.first.units.Units.Rotations;
|
import static edu.wpi.first.units.Units.Rotations;
|
||||||
|
import static edu.wpi.first.units.Units.RotationsPerSecond;
|
||||||
|
import static edu.wpi.first.units.Units.RotationsPerSecondPerSecond;
|
||||||
|
|
||||||
import com.ctre.phoenix6.controls.DutyCycleOut;
|
import com.ctre.phoenix6.controls.DutyCycleOut;
|
||||||
import com.ctre.phoenix6.controls.PositionDutyCycle;
|
import com.ctre.phoenix6.controls.PositionDutyCycle;
|
||||||
@@ -15,44 +18,24 @@ import edu.wpi.first.units.measure.Acceleration;
|
|||||||
import edu.wpi.first.units.measure.Angle;
|
import edu.wpi.first.units.measure.Angle;
|
||||||
import edu.wpi.first.units.measure.Velocity;
|
import edu.wpi.first.units.measure.Velocity;
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
|
import edu.wpi.first.wpilibj.DutyCycleEncoder;
|
||||||
|
|
||||||
public class IntakeReal implements IntakeIO {
|
public class IntakeReal implements IntakeIO {
|
||||||
|
|
||||||
TalonFX m_armMotor;
|
SparkMax m_armMotor;
|
||||||
SparkMax m_rollerMotor;
|
SparkMax m_rollerMotor;
|
||||||
DigitalInput m_armLimitSwitch;
|
DutyCycleEncoder encoder;
|
||||||
|
|
||||||
PositionDutyCycle armPosition = new PositionDutyCycle(0);
|
|
||||||
DutyCycleOut armPercentOutput = new DutyCycleOut(0);
|
|
||||||
|
|
||||||
public IntakeReal(
|
public IntakeReal(
|
||||||
DigitalInput armLimitSwitch,
|
// DigitalInput armLimitSwitch,
|
||||||
TalonFX armMotor,
|
SparkMax armMotor,
|
||||||
SparkMax rollerMotor
|
SparkMax rollerMotor
|
||||||
) {
|
) {
|
||||||
// m_angleMotor = angleMotor;
|
// m_angleMotor = angleMotor;
|
||||||
// m_pitchMotor = pitchMotor;
|
// m_pitchMotor = pitchMotor;
|
||||||
m_armMotor = armMotor;
|
m_armMotor = armMotor;
|
||||||
m_rollerMotor = rollerMotor;
|
m_rollerMotor = rollerMotor;
|
||||||
m_armLimitSwitch = armLimitSwitch;
|
// m_armLimitSwitch = armLimitSwitch;
|
||||||
|
|
||||||
// Apply the configs
|
|
||||||
m_armMotor.getConfigurator().apply(IntakeConstants.ARM_PID);
|
|
||||||
m_armMotor.getConfigurator().apply(IntakeConstants.ARM_MOTOR_CONFIG);
|
|
||||||
// m_rollerMotor.getConfigurator().apply(IntakeConstants.ROLLER_MOTOR_CONFIG);
|
|
||||||
|
|
||||||
armPosition.Slot = 0;
|
|
||||||
// rollerVelocity.Slot = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
private Angle clampAng(Angle x, Angle min, Angle max){
|
|
||||||
if(x.gt(max)) {
|
|
||||||
return max;
|
|
||||||
}else if(x.lt(min)) {
|
|
||||||
return min;
|
|
||||||
}else{
|
|
||||||
return x;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -77,40 +60,14 @@ public class IntakeReal implements IntakeIO {
|
|||||||
Angle motorAngle = angle.times(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
|
Angle motorAngle = angle.times(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
|
||||||
|
|
||||||
// PositionDutyCycle posRequest = new PositionDutyCycle(motorTargetAngle);
|
// PositionDutyCycle posRequest = new PositionDutyCycle(motorTargetAngle);
|
||||||
m_armMotor.setControl(
|
// m_armMotor.setControl(
|
||||||
armPosition
|
// armPosition
|
||||||
.withPosition(motorAngle)
|
// .withPosition(motorAngle)
|
||||||
.withLimitReverseMotion(!m_armLimitSwitch.get())
|
// .withLimitReverseMotion(!m_armLimitSwitch.get())
|
||||||
);
|
// );
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
|
||||||
public void testSetArmAngle(IntakeState state, Angle angle){
|
|
||||||
state.armTargetAngle = angle;
|
|
||||||
Angle motorAngle = angle.times(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
|
|
||||||
|
|
||||||
final TrapezoidProfile m_profile = new TrapezoidProfile(
|
|
||||||
new TrapezoidProfile.Constraints(80, 160)
|
|
||||||
);
|
|
||||||
|
|
||||||
// Final target of motorAngle rot, 0 rps
|
|
||||||
// Convert the Angle to a numeric degree value before creating the profile state
|
|
||||||
TrapezoidProfile.State m_goal = new TrapezoidProfile.State(motorAngle.in(Rotations), 0);
|
|
||||||
TrapezoidProfile.State m_setpoint = new TrapezoidProfile.State();
|
|
||||||
|
|
||||||
// create a position closed-loop request, voltage output, slot 0 configs
|
|
||||||
final PositionVoltage m_request = new PositionVoltage(0).withSlot(0);
|
|
||||||
|
|
||||||
// calculate the next profile setpoint
|
|
||||||
m_setpoint = m_profile.calculate(0.020, m_setpoint, m_goal);
|
|
||||||
|
|
||||||
// send the request to the device
|
|
||||||
m_request.Position = m_setpoint.position;
|
|
||||||
m_request.Velocity = m_setpoint.velocity;
|
|
||||||
m_armMotor.setControl(m_request);
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void stopArm(){
|
public void stopArm(){
|
||||||
m_armMotor.set(0);
|
m_armMotor.set(0);
|
||||||
@@ -119,36 +76,33 @@ public class IntakeReal implements IntakeIO {
|
|||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void armOutput(double percentOutput){
|
public void armOutput(double percentOutput){
|
||||||
m_armMotor.setControl(
|
m_armMotor.set(percentOutput);
|
||||||
armPercentOutput.withOutput(percentOutput)
|
|
||||||
.withLimitReverseMotion(!m_armLimitSwitch.get())
|
|
||||||
);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void updateInputs(IntakeState state) {
|
public void updateInputs(IntakeState state) {
|
||||||
state.armAngle = m_armMotor.getPosition().getValue().div(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
|
state.armAngle = Rotations.of(m_armMotor.getEncoder().getPosition()).div(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
|
||||||
state.armMotorCurrent = m_armMotor.getStatorCurrent().getValue();
|
state.armMotorVelocity = RotationsPerSecond.of(m_armMotor.getEncoder().getVelocity()).div(IntakeConstants.ARM_MOTOR_GEAR_RATIO);
|
||||||
|
// state.armMotorAcceleration = RotationsPerSecondPerSecond.of(m_armMotor.getEncoder().ge);
|
||||||
|
state.armMotorCurrent = Amps.of(m_armMotor.getOutputCurrent());
|
||||||
|
|
||||||
state.rollerOutput = m_rollerMotor.get();
|
state.rollerOutput = m_rollerMotor.get();
|
||||||
state.rollerMotorCurrent = Amps.of(m_rollerMotor.getOutputCurrent());
|
state.rollerMotorCurrent = Amps.of(m_rollerMotor.getOutputCurrent());
|
||||||
state.retractedLimit = !m_armLimitSwitch.get();
|
|
||||||
|
|
||||||
state.armMotorVelocity = m_armMotor.getVelocity().getValue();
|
|
||||||
state.armMotorAcceleration = m_armMotor.getAcceleration().getValue();
|
|
||||||
|
|
||||||
if(state.retractedLimit) {
|
// if(state.retractedLimit) {
|
||||||
// Set the arm motor to be zero if the limit switch is pressed
|
// // Set the arm motor to be zero if the limit switch is pressed
|
||||||
m_armMotor.setPosition(0., 0);
|
// m_armMotor.setPosition(0., 0);
|
||||||
}
|
// }
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void updateGains() {
|
public void updateGains() {
|
||||||
|
|
||||||
IntakeConstants.ARM_PID.kP = IntakeConstants.arm_kP.get();
|
// IntakeConstants.ARM_PID.kP = IntakeConstants.arm_kP.get();
|
||||||
IntakeConstants.ARM_PID.kI = IntakeConstants.arm_kI.get();
|
// IntakeConstants.ARM_PID.kI = IntakeConstants.arm_kI.get();
|
||||||
IntakeConstants.ARM_PID.kD = IntakeConstants.arm_kD.get();
|
// IntakeConstants.ARM_PID.kD = IntakeConstants.arm_kD.get();
|
||||||
m_armMotor.getConfigurator().apply(IntakeConstants.ARM_PID);
|
// m_armMotor.getConfigurator().apply(IntakeConstants.ARM_PID);
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
{
|
{
|
||||||
"fileName": "AdvantageKit.json",
|
"fileName": "AdvantageKit.json",
|
||||||
"name": "AdvantageKit",
|
"name": "AdvantageKit",
|
||||||
"version": "26.0.0",
|
"version": "26.0.2",
|
||||||
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
|
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
|
||||||
"frcYear": "2026",
|
"frcYear": "2026",
|
||||||
"mavenUrls": [
|
"mavenUrls": [
|
||||||
@@ -12,14 +12,14 @@
|
|||||||
{
|
{
|
||||||
"groupId": "org.littletonrobotics.akit",
|
"groupId": "org.littletonrobotics.akit",
|
||||||
"artifactId": "akit-java",
|
"artifactId": "akit-java",
|
||||||
"version": "26.0.0"
|
"version": "26.0.2"
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
"jniDependencies": [
|
"jniDependencies": [
|
||||||
{
|
{
|
||||||
"groupId": "org.littletonrobotics.akit",
|
"groupId": "org.littletonrobotics.akit",
|
||||||
"artifactId": "akit-wpilibio",
|
"artifactId": "akit-wpilibio",
|
||||||
"version": "26.0.0",
|
"version": "26.0.2",
|
||||||
"skipInvalidPlatforms": false,
|
"skipInvalidPlatforms": false,
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
{
|
{
|
||||||
"fileName": "Phoenix6-26.1.0.json",
|
"fileName": "Phoenix6-26.1.3.json",
|
||||||
"name": "CTRE-Phoenix (v6)",
|
"name": "CTRE-Phoenix (v6)",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"frcYear": "2026",
|
"frcYear": "2026",
|
||||||
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
|
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
|
||||||
"mavenUrls": [
|
"mavenUrls": [
|
||||||
@@ -19,14 +19,14 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6",
|
"groupId": "com.ctre.phoenix6",
|
||||||
"artifactId": "wpiapi-java",
|
"artifactId": "wpiapi-java",
|
||||||
"version": "26.1.0"
|
"version": "26.1.3"
|
||||||
}
|
}
|
||||||
],
|
],
|
||||||
"jniDependencies": [
|
"jniDependencies": [
|
||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6",
|
"groupId": "com.ctre.phoenix6",
|
||||||
"artifactId": "api-cpp",
|
"artifactId": "api-cpp",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -40,7 +40,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6",
|
"groupId": "com.ctre.phoenix6",
|
||||||
"artifactId": "tools",
|
"artifactId": "tools",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -54,7 +54,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "api-cpp-sim",
|
"artifactId": "api-cpp-sim",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -68,7 +68,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "tools-sim",
|
"artifactId": "tools-sim",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -82,7 +82,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simTalonSRX",
|
"artifactId": "simTalonSRX",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -96,7 +96,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simVictorSPX",
|
"artifactId": "simVictorSPX",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -110,7 +110,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simPigeonIMU",
|
"artifactId": "simPigeonIMU",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -124,7 +124,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProTalonFX",
|
"artifactId": "simProTalonFX",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -138,7 +138,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProTalonFXS",
|
"artifactId": "simProTalonFXS",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -152,7 +152,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProCANcoder",
|
"artifactId": "simProCANcoder",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -166,7 +166,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProPigeon2",
|
"artifactId": "simProPigeon2",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -180,7 +180,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProCANrange",
|
"artifactId": "simProCANrange",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -194,7 +194,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProCANdi",
|
"artifactId": "simProCANdi",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -208,7 +208,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProCANdle",
|
"artifactId": "simProCANdle",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -224,7 +224,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6",
|
"groupId": "com.ctre.phoenix6",
|
||||||
"artifactId": "wpiapi-cpp",
|
"artifactId": "wpiapi-cpp",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_Phoenix6_WPI",
|
"libName": "CTRE_Phoenix6_WPI",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -240,7 +240,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6",
|
"groupId": "com.ctre.phoenix6",
|
||||||
"artifactId": "tools",
|
"artifactId": "tools",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_PhoenixTools",
|
"libName": "CTRE_PhoenixTools",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -256,7 +256,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "wpiapi-cpp-sim",
|
"artifactId": "wpiapi-cpp-sim",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_Phoenix6_WPISim",
|
"libName": "CTRE_Phoenix6_WPISim",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -272,7 +272,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "tools-sim",
|
"artifactId": "tools-sim",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_PhoenixTools_Sim",
|
"libName": "CTRE_PhoenixTools_Sim",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -288,7 +288,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simTalonSRX",
|
"artifactId": "simTalonSRX",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimTalonSRX",
|
"libName": "CTRE_SimTalonSRX",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -304,7 +304,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simVictorSPX",
|
"artifactId": "simVictorSPX",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimVictorSPX",
|
"libName": "CTRE_SimVictorSPX",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -320,7 +320,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simPigeonIMU",
|
"artifactId": "simPigeonIMU",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimPigeonIMU",
|
"libName": "CTRE_SimPigeonIMU",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -336,7 +336,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProTalonFX",
|
"artifactId": "simProTalonFX",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimProTalonFX",
|
"libName": "CTRE_SimProTalonFX",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -352,7 +352,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProTalonFXS",
|
"artifactId": "simProTalonFXS",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimProTalonFXS",
|
"libName": "CTRE_SimProTalonFXS",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -368,7 +368,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProCANcoder",
|
"artifactId": "simProCANcoder",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimProCANcoder",
|
"libName": "CTRE_SimProCANcoder",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -384,7 +384,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProPigeon2",
|
"artifactId": "simProPigeon2",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimProPigeon2",
|
"libName": "CTRE_SimProPigeon2",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -400,7 +400,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProCANrange",
|
"artifactId": "simProCANrange",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimProCANrange",
|
"libName": "CTRE_SimProCANrange",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -416,7 +416,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProCANdi",
|
"artifactId": "simProCANdi",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimProCANdi",
|
"libName": "CTRE_SimProCANdi",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -432,7 +432,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "com.ctre.phoenix6.sim",
|
"groupId": "com.ctre.phoenix6.sim",
|
||||||
"artifactId": "simProCANdle",
|
"artifactId": "simProCANdle",
|
||||||
"version": "26.1.0",
|
"version": "26.1.3",
|
||||||
"libName": "CTRE_SimProCANdle",
|
"libName": "CTRE_SimProCANdle",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -1,7 +1,7 @@
|
|||||||
{
|
{
|
||||||
"fileName": "photonlib.json",
|
"fileName": "photonlib.json",
|
||||||
"name": "photonlib",
|
"name": "photonlib",
|
||||||
"version": "v2025.3.1",
|
"version": "v2026.3.2",
|
||||||
"uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004",
|
"uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004",
|
||||||
"frcYear": "2026",
|
"frcYear": "2026",
|
||||||
"mavenUrls": [
|
"mavenUrls": [
|
||||||
@@ -13,7 +13,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "org.photonvision",
|
"groupId": "org.photonvision",
|
||||||
"artifactId": "photontargeting-cpp",
|
"artifactId": "photontargeting-cpp",
|
||||||
"version": "v2025.3.1",
|
"version": "v2026.3.2",
|
||||||
"skipInvalidPlatforms": true,
|
"skipInvalidPlatforms": true,
|
||||||
"isJar": false,
|
"isJar": false,
|
||||||
"validPlatforms": [
|
"validPlatforms": [
|
||||||
@@ -28,7 +28,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "org.photonvision",
|
"groupId": "org.photonvision",
|
||||||
"artifactId": "photonlib-cpp",
|
"artifactId": "photonlib-cpp",
|
||||||
"version": "v2025.3.1",
|
"version": "v2026.3.2",
|
||||||
"libName": "photonlib",
|
"libName": "photonlib",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -43,7 +43,7 @@
|
|||||||
{
|
{
|
||||||
"groupId": "org.photonvision",
|
"groupId": "org.photonvision",
|
||||||
"artifactId": "photontargeting-cpp",
|
"artifactId": "photontargeting-cpp",
|
||||||
"version": "v2025.3.1",
|
"version": "v2026.3.2",
|
||||||
"libName": "photontargeting",
|
"libName": "photontargeting",
|
||||||
"headerClassifier": "headers",
|
"headerClassifier": "headers",
|
||||||
"sharedLibrary": true,
|
"sharedLibrary": true,
|
||||||
@@ -60,12 +60,12 @@
|
|||||||
{
|
{
|
||||||
"groupId": "org.photonvision",
|
"groupId": "org.photonvision",
|
||||||
"artifactId": "photonlib-java",
|
"artifactId": "photonlib-java",
|
||||||
"version": "v2025.3.1"
|
"version": "v2026.3.2"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"groupId": "org.photonvision",
|
"groupId": "org.photonvision",
|
||||||
"artifactId": "photontargeting-java",
|
"artifactId": "photontargeting-java",
|
||||||
"version": "v2025.3.1"
|
"version": "v2026.3.2"
|
||||||
}
|
}
|
||||||
]
|
]
|
||||||
}
|
}
|
||||||
Reference in New Issue
Block a user