Compare commits
6 Commits
brad_eleva
...
eb00b1146e
| Author | SHA1 | Date | |
|---|---|---|---|
| eb00b1146e | |||
| 87e7eb4974 | |||
| 44a036f420 | |||
| a145c290fd | |||
| 3dafb3c269 | |||
| 1c64d7344b |
19
src/main/deploy/pathplanner/autos/fein.auto
Normal file
19
src/main/deploy/pathplanner/autos/fein.auto
Normal file
@@ -0,0 +1,19 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"command": {
|
||||
"type": "sequential",
|
||||
"data": {
|
||||
"commands": [
|
||||
{
|
||||
"type": "path",
|
||||
"data": {
|
||||
"pathName": "fein"
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
"resetOdom": true,
|
||||
"folder": null,
|
||||
"choreoAuto": false
|
||||
}
|
||||
70
src/main/deploy/pathplanner/paths/fein.path
Normal file
70
src/main/deploy/pathplanner/paths/fein.path
Normal file
@@ -0,0 +1,70 @@
|
||||
{
|
||||
"version": "2025.0",
|
||||
"waypoints": [
|
||||
{
|
||||
"anchor": {
|
||||
"x": 7.600204918039607,
|
||||
"y": 6.374590163938041
|
||||
},
|
||||
"prevControl": null,
|
||||
"nextControl": {
|
||||
"x": 7.600204918032786,
|
||||
"y": 7.573360655737705
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 4.459426229508197,
|
||||
"y": 5.978995901639344
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 5.370491803278689,
|
||||
"y": 5.978995901639344
|
||||
},
|
||||
"nextControl": {
|
||||
"x": 2.995158619919281,
|
||||
"y": 5.978995901639344
|
||||
},
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
},
|
||||
{
|
||||
"anchor": {
|
||||
"x": 1.6543032786885246,
|
||||
"y": 6.254713114754098
|
||||
},
|
||||
"prevControl": {
|
||||
"x": 2.613319672131147,
|
||||
"y": 6.278688524590164
|
||||
},
|
||||
"nextControl": null,
|
||||
"isLocked": false,
|
||||
"linkedName": null
|
||||
}
|
||||
],
|
||||
"rotationTargets": [],
|
||||
"constraintZones": [],
|
||||
"pointTowardsZones": [],
|
||||
"eventMarkers": [],
|
||||
"globalConstraints": {
|
||||
"maxVelocity": 4.0,
|
||||
"maxAcceleration": 4.0,
|
||||
"maxAngularVelocity": 540.0,
|
||||
"maxAngularAcceleration": 720.0,
|
||||
"nominalVoltage": 12.0,
|
||||
"unlimited": false
|
||||
},
|
||||
"goalEndState": {
|
||||
"velocity": 0,
|
||||
"rotation": 90.0
|
||||
},
|
||||
"reversed": false,
|
||||
"folder": null,
|
||||
"idealStartingState": {
|
||||
"velocity": 0,
|
||||
"rotation": -90.0
|
||||
},
|
||||
"useDefaultConstraints": true
|
||||
}
|
||||
@@ -53,9 +53,10 @@ public class RobotContainer {
|
||||
|
||||
climberRollers = new ClimberRollers();
|
||||
|
||||
//vision = new Vision(drivetrain::getGyroValue);
|
||||
drivetrain = new Drivetrain();
|
||||
|
||||
vision = new Vision(drivetrain::getGyroValue);
|
||||
|
||||
elevator = new Elevator();
|
||||
//elevator = new ElevatorSysID();
|
||||
|
||||
@@ -70,6 +71,7 @@ public class RobotContainer {
|
||||
|
||||
configureButtonBindings();
|
||||
//elevatorSysIDBindings();
|
||||
//elevatorOnlyBindings();
|
||||
|
||||
configureNamedCommands();
|
||||
|
||||
@@ -85,6 +87,13 @@ public class RobotContainer {
|
||||
operator.y().whileTrue(elevator.sysIdDynamic(Direction.kReverse));
|
||||
}*/
|
||||
|
||||
private void elevatorOnlyBindings(){
|
||||
elevator.setDefaultCommand(elevator.maintainPosition());
|
||||
manipulatorPivot.setDefaultCommand(manipulatorPivot.maintainPosition());
|
||||
|
||||
driver.a().onTrue(safeMoveManipulator(ElevatorConstants.kL2Position, ManipulatorPivotConstants.kL2Position));
|
||||
}
|
||||
|
||||
private void configureButtonBindings() {
|
||||
//Default commands
|
||||
climberPivot.setDefaultCommand(
|
||||
@@ -116,7 +125,7 @@ public class RobotContainer {
|
||||
|
||||
manipulator.setDefaultCommand(
|
||||
manipulator.runUntilCollected(
|
||||
() -> 0
|
||||
() -> 0.0
|
||||
)
|
||||
);
|
||||
|
||||
@@ -127,22 +136,33 @@ public class RobotContainer {
|
||||
);
|
||||
|
||||
driver.rightTrigger().whileTrue(
|
||||
manipulator.runManipulator(() -> 1, true)
|
||||
manipulator.runManipulator(() -> 0.35, true)
|
||||
);
|
||||
|
||||
driver.leftTrigger().whileTrue(
|
||||
manipulator.runUntilCollected(() -> 0.75)
|
||||
manipulator.runUntilCollected(() -> 0.35)
|
||||
);
|
||||
|
||||
driver.leftBumper().whileTrue(
|
||||
manipulator.runUntilCollected(() -> 0.5)
|
||||
);
|
||||
|
||||
driver.rightBumper().whileTrue(
|
||||
manipulator.runManipulator(() -> 1, false)
|
||||
);
|
||||
|
||||
driver.start().and(driver.back()).onTrue(
|
||||
startingConfig()
|
||||
);
|
||||
|
||||
driver.y().whileTrue(drivetrain.zeroHeading());
|
||||
|
||||
driver.povDown().whileTrue(climberPivot.runPivot(-0.5));
|
||||
driver.povUp().whileTrue(climberPivot.runPivot(0.5));
|
||||
|
||||
driver.povLeft().whileTrue(climberRollers.runRoller(0.5));
|
||||
driver.povRight().whileTrue(climberRollers.runRoller(-0.5));
|
||||
driver.a().whileTrue(manipulator.runManipulator(() -> 0.5, false));
|
||||
|
||||
//Operator inputs
|
||||
operator.povUp().onTrue(
|
||||
@@ -174,22 +194,17 @@ public class RobotContainer {
|
||||
);
|
||||
|
||||
operator.a().onTrue(
|
||||
coralIntakeRoutine()
|
||||
safeMoveManipulator(ElevatorConstants.kL1Position, 0.0)
|
||||
);
|
||||
|
||||
operator.x().onTrue(
|
||||
algaeIntakeRoutine(true)
|
||||
safeMoveManipulator(ElevatorConstants.kL2AlgaePosition, ManipulatorPivotConstants.kL2AlgaePosition)
|
||||
);
|
||||
|
||||
operator.b().onTrue(
|
||||
algaeIntakeRoutine(false)
|
||||
safeMoveManipulator(ElevatorConstants.kL3AlgaePosition, ManipulatorPivotConstants.kL3AlgaePosition)
|
||||
);
|
||||
|
||||
operator.y().whileTrue(
|
||||
elevator.goToSetpoint(() -> ElevatorConstants.kL2Position)
|
||||
);
|
||||
|
||||
|
||||
}
|
||||
|
||||
private void configureNamedCommands() {
|
||||
@@ -244,12 +259,22 @@ public class RobotContainer {
|
||||
sensorTab.addDouble("ElevMotor2", elevator::getMotor2)
|
||||
.withWidget(BuiltInWidgets.kGraph);
|
||||
|
||||
sensorTab.addDouble("Elevator setpoint", elevator::getPIDSetpoint)
|
||||
sensorTab.addDouble("Elevator setpoint up", elevator::getPIDUpSetpoint)
|
||||
.withSize(1, 1)
|
||||
.withPosition(5, 0)
|
||||
.withWidget(BuiltInWidgets.kTextView);
|
||||
|
||||
sensorTab.addDouble("Elevator error", elevator::getPIDError)
|
||||
sensorTab.addDouble("Elevator error up", elevator::getPIDUpError)
|
||||
.withSize(1, 1)
|
||||
.withPosition(5, 1)
|
||||
.withWidget(BuiltInWidgets.kTextView);
|
||||
|
||||
sensorTab.addDouble("Elevator setpoint down", elevator::getPIDDownSetpoint)
|
||||
.withSize(1, 1)
|
||||
.withPosition(5, 0)
|
||||
.withWidget(BuiltInWidgets.kTextView);
|
||||
|
||||
sensorTab.addDouble("Elevator error down", elevator::getPIDDownError)
|
||||
.withSize(1, 1)
|
||||
.withPosition(5, 1)
|
||||
.withWidget(BuiltInWidgets.kTextView);
|
||||
@@ -258,6 +283,9 @@ public class RobotContainer {
|
||||
|
||||
sensorTab.addDouble("manipulator cg position", manipulatorPivot::getCGPosition);
|
||||
|
||||
sensorTab.addDouble("dt distance", drivetrain::driveDistance);
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -381,10 +409,13 @@ public class RobotContainer {
|
||||
* @param armPosition The target rotation of the arm
|
||||
* @return Moves the elevator and arm to the setpoints
|
||||
*/
|
||||
@SuppressWarnings("unused")
|
||||
private Command safeMoveManipulator(double elevatorPosition, double armPosition) {
|
||||
return moveManipulatorUtil(elevatorPosition, ManipulatorPivotConstants.kPivotSafeStowPosition, false, true)
|
||||
.andThen(manipulatorPivot.goToSetpoint(() -> armPosition));
|
||||
/*return moveManipulatorUtil(elevatorPosition, ManipulatorPivotConstants.kPivotSafeStowPosition, false, true)
|
||||
.deadlineFor(manipulatorPivot.goToSetpoint(() -> armPosition),
|
||||
elevator.maintainPosition());*/
|
||||
return manipulatorPivot.goToSetpoint(() -> ManipulatorPivotConstants.kPivotSafeStowPosition)
|
||||
.andThen(elevator.goToSetpoint(() -> elevatorPosition), manipulatorPivot.goToSetpoint(() -> armPosition)
|
||||
.raceWith(elevator.maintainPosition()));
|
||||
}
|
||||
|
||||
@SuppressWarnings("unused")
|
||||
|
||||
@@ -13,7 +13,7 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
|
||||
public class DrivetrainConstants {
|
||||
// Driving Parameters - Note that these are not the maximum capable speeds of
|
||||
// the robot, rather the allowed maximum speeds
|
||||
public static final double kMaxSpeedMetersPerSecond = 4.8;
|
||||
public static final double kMaxSpeedMetersPerSecond = 5.5;
|
||||
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
|
||||
|
||||
// Chassis configuration
|
||||
|
||||
@@ -41,16 +41,18 @@ public class ElevatorConstants {
|
||||
|
||||
public static final double kCoralIntakePosition = 0;
|
||||
public static final double kL1Position = 0;
|
||||
public static final double kL2Position = 14.5;
|
||||
public static final double kL3Position = 29.0;
|
||||
public static final double kL4Position = 53.0;
|
||||
public static final double kL2Position = 8;
|
||||
public static final double kL3Position = 25.0;
|
||||
public static final double kL4Position = 50.5;
|
||||
public static final double kL4TransitionPosition = 40.0;
|
||||
public static final double kL2AlgaePosition = 22.0;
|
||||
public static final double kL2AlgaePosition = 21.0;
|
||||
public static final double kL3AlgaePosition = 39.0;
|
||||
public static final double kProcessorPosition = 4.0;
|
||||
/**The position of the top of the elevator brace */
|
||||
public static final double kBracePosition = 0;
|
||||
public static final double kMaxHeight = 47.5; //actual is 53
|
||||
public static final double kMaxHeight = 51.0; //actual is 51
|
||||
|
||||
public static final double kVoltageLimit = 7;
|
||||
|
||||
// 1, 7, 10 are the defaults for these, change as necessary
|
||||
public static final double kSysIDRampRate = .25;
|
||||
|
||||
@@ -34,19 +34,19 @@ public class ManipulatorPivotConstants {
|
||||
public static final double kMaxAcceleration = Units.degreesToRadians(1000.0); // degrees per second^2 calculated max = 2100
|
||||
public static final double kMaxVelocity = Units.degreesToRadians(100.0); // degrees per second calculated max = 168
|
||||
|
||||
public static final double kEncoderOffset = 0.7815;
|
||||
public static final double kEncoderOffset = 0.780;
|
||||
|
||||
public static final double kCoralIntakePosition = Units.degreesToRadians(175.0);
|
||||
public static final double kL1Position = Units.degreesToRadians(0.0);
|
||||
public static final double kL2Position = Units.degreesToRadians(60.0);
|
||||
public static final double kL3Position = Units.degreesToRadians(60.0);
|
||||
public static final double kL2Position = Units.degreesToRadians(22.0);
|
||||
public static final double kL3Position = Units.degreesToRadians(22.0);
|
||||
public static final double kL4Position = Units.degreesToRadians(45.0);
|
||||
public static final double kL2AlgaePosition = Units.degreesToRadians(175.0);
|
||||
public static final double kL3AlgaePosition = Units.degreesToRadians(175.0);
|
||||
public static final double kProcesserPosition = Units.degreesToRadians(175.0);
|
||||
public static final double kNetPosition = Units.degreesToRadians(175.0);
|
||||
/**The closest position to the elevator brace without hitting it */
|
||||
public static final double kPivotSafeStowPosition = Units.degreesToRadians(67.0);
|
||||
public static final double kPivotSafeStowPosition = Units.degreesToRadians(71.0);
|
||||
/**The forward rotation limit of the pivot */
|
||||
public static final double kRotationLimit = Units.degreesToRadians(175.0);
|
||||
|
||||
|
||||
@@ -22,7 +22,7 @@ public class ModuleConstants {
|
||||
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
|
||||
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15
|
||||
// teeth on the bevel pinion
|
||||
public static final double kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15);
|
||||
public static final double kDrivingMotorReduction = (45.0 * 20) / (kDrivingMotorPinionTeeth * 15);
|
||||
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
|
||||
/ kDrivingMotorReduction;
|
||||
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class NeoMotorConstants {
|
||||
public static final double kFreeSpeedRpm = 5676;
|
||||
public static final double kFreeSpeedRpm = 6000; //for kraken not neo
|
||||
}
|
||||
|
||||
@@ -248,9 +248,12 @@ public class Drivetrain extends SubsystemBase {
|
||||
m_rearRight.resetEncoders();
|
||||
}
|
||||
|
||||
/** Zeroes the heading of the robot. */
|
||||
public void zeroHeading() {
|
||||
gyro.reset();
|
||||
/** Zeroes the heading of the robot.
|
||||
* @return */
|
||||
public Command zeroHeading() {
|
||||
return run(() -> {
|
||||
gyro.reset();
|
||||
});
|
||||
}
|
||||
|
||||
public double getGyroValue() {
|
||||
@@ -278,4 +281,8 @@ public class Drivetrain extends SubsystemBase {
|
||||
public void addVisionMeasurement(Pose2d pose, double timestamp){
|
||||
m_estimator.addVisionMeasurement(pose, timestamp);
|
||||
}
|
||||
|
||||
public double driveDistance(){
|
||||
return m_frontLeft.getTotalDist();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -24,7 +24,8 @@ public class Elevator extends SubsystemBase {
|
||||
|
||||
private DigitalInput bottomLimitSwitch;
|
||||
|
||||
private PIDController pidController;
|
||||
private PIDController pidControllerUp;
|
||||
private PIDController pidControllerDown;
|
||||
|
||||
private ElevatorFeedforward feedForward;
|
||||
|
||||
@@ -57,14 +58,25 @@ public class Elevator extends SubsystemBase {
|
||||
ElevatorConstants.kBottomLimitSwitchID
|
||||
);
|
||||
|
||||
pidController = new PIDController(
|
||||
pidControllerDown = new PIDController(
|
||||
ElevatorConstants.kDownControllerP,
|
||||
ElevatorConstants.kDownControllerI,
|
||||
ElevatorConstants.kDownControllerD
|
||||
);
|
||||
pidController.setSetpoint(0);
|
||||
pidControllerDown.setSetpoint(0);
|
||||
|
||||
pidController.setTolerance(ElevatorConstants.kAllowedError);
|
||||
pidControllerDown.setTolerance(ElevatorConstants.kAllowedError);
|
||||
|
||||
pidControllerUp = new PIDController(
|
||||
ElevatorConstants.kUpControllerP,
|
||||
ElevatorConstants.kUpControllerI,
|
||||
ElevatorConstants.kUpControllerD
|
||||
);
|
||||
pidControllerUp.setSetpoint(0);
|
||||
|
||||
pidControllerUp.setTolerance(ElevatorConstants.kAllowedError);
|
||||
|
||||
|
||||
|
||||
feedForward = new ElevatorFeedforward(
|
||||
ElevatorConstants.kFeedForwardS,
|
||||
@@ -131,54 +143,34 @@ public class Elevator extends SubsystemBase {
|
||||
public Command maintainPosition() {
|
||||
|
||||
return startRun(() -> {
|
||||
|
||||
//pidController.reset();
|
||||
// pidController.setSetpoint(encoder.getPosition());
|
||||
/*
|
||||
pidControllerUp.reset();
|
||||
pidControllerDown.reset();
|
||||
*/
|
||||
},
|
||||
() -> {
|
||||
/*if (!pidController.atSetpoint()) {
|
||||
elevatorMotor1.setVoltage(
|
||||
pidController.calculate(
|
||||
encoder.getPosition()
|
||||
) + feedForward.calculate(0)
|
||||
/*
|
||||
double upOutput = pidControllerUp.calculate(getEncoderPosition());
|
||||
double downOutput = pidControllerDown.calculate(getEncoderPosition());
|
||||
|
||||
if(pidControllerUp.getSetpoint()>encoder.getPosition())
|
||||
elevatorMotor1.setVoltage( MathUtil.clamp(
|
||||
upOutput + feedForward.calculate(0), -1, 1)
|
||||
);
|
||||
} else {
|
||||
else{
|
||||
elevatorMotor1.setVoltage(
|
||||
feedForward.calculate(0)
|
||||
MathUtil.clamp(
|
||||
downOutput + feedForward.calculate(0), -1, 1)
|
||||
);
|
||||
}*/
|
||||
}
|
||||
*/
|
||||
|
||||
elevatorMotor1.setVoltage(
|
||||
feedForward.calculate(0)
|
||||
);
|
||||
|
||||
});
|
||||
|
||||
|
||||
|
||||
|
||||
/*
|
||||
elevatorMotor1.setVoltage(
|
||||
pidController.calculate(
|
||||
encoder.getPosition(),
|
||||
clampedSetpoint
|
||||
) + feedForward.calculate(0)
|
||||
);
|
||||
*/
|
||||
/*
|
||||
if (!pidController.atSetpoint()) {
|
||||
elevatorMotor1.setVoltage(
|
||||
pidController.calculate(
|
||||
encoder.getPosition(),
|
||||
clampedSetpoint
|
||||
) + feedForward.calculate(0)
|
||||
);
|
||||
} else {
|
||||
elevatorMotor1.setVoltage(
|
||||
feedForward.calculate(0)
|
||||
);
|
||||
}
|
||||
|
||||
});*/
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -189,29 +181,62 @@ public class Elevator extends SubsystemBase {
|
||||
* @return Sets motor voltage to achieve the target destination
|
||||
*/
|
||||
public Command goToSetpoint(DoubleSupplier setpoint) {
|
||||
|
||||
if (setpoint.getAsDouble() == 0) {
|
||||
return startRun(() -> {
|
||||
|
||||
pidControllerUp.reset();
|
||||
pidControllerDown.reset();
|
||||
pidControllerUp.setSetpoint(setpoint.getAsDouble());
|
||||
pidControllerDown.setSetpoint(setpoint.getAsDouble());
|
||||
|
||||
},
|
||||
() -> {
|
||||
double upOutput = pidControllerUp.calculate(getEncoderPosition());
|
||||
double downOutput = pidControllerDown.calculate(getEncoderPosition());
|
||||
|
||||
if(setpoint.getAsDouble()>encoder.getPosition())
|
||||
elevatorMotor1.setVoltage( MathUtil.clamp(
|
||||
upOutput + feedForward.calculate(0), ElevatorConstants.kVoltageLimit * -1, ElevatorConstants.kVoltageLimit)
|
||||
);
|
||||
else{
|
||||
elevatorMotor1.setVoltage(
|
||||
MathUtil.clamp(
|
||||
downOutput + feedForward.calculate(0), ElevatorConstants.kVoltageLimit * -1, ElevatorConstants.kVoltageLimit)
|
||||
);
|
||||
}
|
||||
|
||||
}).until(() -> pidControllerUp.atSetpoint() || pidControllerDown.atSetpoint())
|
||||
.andThen(runManualElevator(() -> -.1)
|
||||
.until(() -> encoder.getPosition() == 0));
|
||||
|
||||
return startRun(() -> {
|
||||
} else {
|
||||
return startRun(() -> {
|
||||
|
||||
pidController.setSetpoint(setpoint.getAsDouble());
|
||||
pidController.reset();
|
||||
},
|
||||
() -> {
|
||||
if (!pidController.atSetpoint()) {
|
||||
elevatorMotor1.setVoltage(
|
||||
pidController.calculate(
|
||||
encoder.getPosition(),
|
||||
setpoint.getAsDouble()
|
||||
) + feedForward.calculate(0)
|
||||
);
|
||||
} else {
|
||||
elevatorMotor1.setVoltage(
|
||||
feedForward.calculate(0)
|
||||
);
|
||||
}
|
||||
}).until(() -> pidController.atSetpoint());
|
||||
pidControllerUp.reset();
|
||||
pidControllerDown.reset();
|
||||
pidControllerUp.setSetpoint(setpoint.getAsDouble());
|
||||
pidControllerDown.setSetpoint(setpoint.getAsDouble());
|
||||
|
||||
},
|
||||
() -> {
|
||||
double upOutput = pidControllerUp.calculate(getEncoderPosition());
|
||||
double downOutput = pidControllerDown.calculate(getEncoderPosition());
|
||||
|
||||
if(setpoint.getAsDouble()>encoder.getPosition())
|
||||
elevatorMotor1.setVoltage( MathUtil.clamp(
|
||||
upOutput + feedForward.calculate(0), ElevatorConstants.kVoltageLimit * -1, ElevatorConstants.kVoltageLimit)
|
||||
);
|
||||
else{
|
||||
elevatorMotor1.setVoltage(
|
||||
MathUtil.clamp(
|
||||
downOutput + feedForward.calculate(0), ElevatorConstants.kVoltageLimit * -1, ElevatorConstants.kVoltageLimit)
|
||||
);
|
||||
}
|
||||
|
||||
}).until(() -> pidControllerUp.atSetpoint() || pidControllerDown.atSetpoint());
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
/*
|
||||
elevatorMotor1.setVoltage(
|
||||
@@ -293,11 +318,19 @@ public class Elevator extends SubsystemBase {
|
||||
return elevatorMotor2.getAppliedOutput()*elevatorMotor2.getBusVoltage();
|
||||
}
|
||||
|
||||
public double getPIDSetpoint() {
|
||||
return pidController.getSetpoint();
|
||||
public double getPIDUpSetpoint() {
|
||||
return pidControllerUp.getSetpoint();
|
||||
}
|
||||
|
||||
public double getPIDError() {
|
||||
return pidController.getError();
|
||||
public double getPIDUpError() {
|
||||
return pidControllerUp.getError();
|
||||
}
|
||||
|
||||
public double getPIDDownSetpoint() {
|
||||
return pidControllerDown.getSetpoint();
|
||||
}
|
||||
|
||||
public double getPIDDownError() {
|
||||
return pidControllerDown.getError();
|
||||
}
|
||||
}
|
||||
@@ -138,4 +138,8 @@ public class MAXSwerveModule {
|
||||
public void resetEncoders() {
|
||||
m_drive.setPosition(0);
|
||||
}
|
||||
|
||||
public double getTotalDist(){
|
||||
return m_drive.getPosition().getValueAsDouble();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -40,9 +40,9 @@ public class Vision{
|
||||
NetworkTable blackVisionTable = inst.getTable("black_Fiducial");
|
||||
NetworkTable orangeVisionTable = inst.getTable("orange_Fiducial");
|
||||
|
||||
blackRobotRelativeX = orangeVisionTable.getDoubleTopic("blackRelativeX").subscribe(0.0);
|
||||
blackRobotRelativeY = orangeVisionTable.getDoubleTopic("blackRelativeY").subscribe(0.0);
|
||||
blackRobotRelativeZ = orangeVisionTable.getDoubleTopic("blackRelativeZ").subscribe(0.0);
|
||||
blackRobotRelativeX = blackVisionTable.getDoubleTopic("blackRelativeX").subscribe(0.0);
|
||||
blackRobotRelativeY = blackVisionTable.getDoubleTopic("blackRelativeY").subscribe(0.0);
|
||||
blackRobotRelativeZ = blackVisionTable.getDoubleTopic("blackRelativeZ").subscribe(0.0);
|
||||
|
||||
blackClosestTag = blackVisionTable.getDoubleTopic("blackClosestTag").subscribe(0.0);
|
||||
blackTagDetected = blackVisionTable.getBooleanTopic("blackTagDetected").subscribe(false);
|
||||
@@ -59,24 +59,23 @@ public class Vision{
|
||||
orangeFramerate = orangeVisionTable.getDoubleTopic("orangeFPS").subscribe(0.0);
|
||||
}
|
||||
|
||||
public Pose2d relativeToGlobalPose2d(int tagID, Translation2d relativeCoords, Rotation2d gyroAngle){
|
||||
public Pose2d relativeToGlobalPose2d(int tagID, Translation2d relativeCoords){
|
||||
Pose2d tag2dPose = new Pose2d(VisionConstants.globalTagCoords[tagID][0],
|
||||
VisionConstants.globalTagCoords[tagID][1],
|
||||
new Rotation2d());
|
||||
|
||||
Pose2d relative = new Pose2d(relativeCoords, gyroAngle);
|
||||
Pose2d relative = new Pose2d(relativeCoords, new Rotation2d(gyroAngle.getAsDouble()));
|
||||
|
||||
Transform2d relative2dTransformation = new Transform2d(relative.getTranslation(), relative.getRotation());
|
||||
|
||||
Pose2d globalPose = tag2dPose.transformBy(relative2dTransformation.inverse());
|
||||
|
||||
return new Pose2d(globalPose.getTranslation(), gyroAngle);
|
||||
return new Pose2d(globalPose.getTranslation(), new Rotation2d(gyroAngle.getAsDouble()));
|
||||
}
|
||||
|
||||
public Pose2d getBlackGlobalPose(){
|
||||
return relativeToGlobalPose2d(getBlackClosestTag(),
|
||||
new Translation2d(getBlackRelativeX(), getBlackRelativeY()),
|
||||
new Rotation2d(gyroAngle.getAsDouble()));
|
||||
new Translation2d(getBlackRelativeX(), getBlackRelativeY()));
|
||||
}
|
||||
|
||||
public double getBlackRelativeX(){
|
||||
@@ -109,8 +108,7 @@ public class Vision{
|
||||
|
||||
public Pose2d getOrangeGlobalPose(){
|
||||
return relativeToGlobalPose2d(getOrangeClosestTag(),
|
||||
new Translation2d(getOrangeRelativeX(), getOrangeRelativeY()),
|
||||
new Rotation2d(gyroAngle.getAsDouble()));
|
||||
new Translation2d(getOrangeRelativeX(), getOrangeRelativeY()));
|
||||
}
|
||||
|
||||
public double getOrangeRelativeX(){
|
||||
|
||||
Reference in New Issue
Block a user