6 Commits

7 changed files with 94 additions and 11 deletions

View File

@@ -0,0 +1,19 @@
{
"version": "2025.0",
"command": {
"type": "sequential",
"data": {
"commands": [
{
"type": "path",
"data": {
"pathName": "Field Oriented Test Path"
}
}
]
}
},
"resetOdom": true,
"folder": null,
"choreoAuto": false
}

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,54 @@
{
"version": "2025.0",
"waypoints": [
{
"anchor": {
"x": 2.0,
"y": 7.0
},
"prevControl": null,
"nextControl": {
"x": 3.0,
"y": 7.0
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 4.495389344262295,
"y": 6.788165983606557
},
"prevControl": {
"x": 3.4164959016393444,
"y": 6.80015368852459
},
"nextControl": null,
"isLocked": false,
"linkedName": null
}
],
"rotationTargets": [],
"constraintZones": [],
"pointTowardsZones": [],
"eventMarkers": [],
"globalConstraints": {
"maxVelocity": 4.0,
"maxAcceleration": 1.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 400.0,
"nominalVoltage": 12.0,
"unlimited": false
},
"goalEndState": {
"velocity": 0,
"rotation": -90.0
},
"reversed": false,
"folder": null,
"idealStartingState": {
"velocity": 0,
"rotation": 0.0
},
"useDefaultConstraints": true
}

View File

@@ -143,7 +143,7 @@ public class RobotContainer {
);
driver.leftTrigger().whileTrue(
manipulator.runUntilCollected(() -> 0.75)
manipulator.runUntilCollected(() -> 0.75).andThen(manipulator.retractCommand(() -> 0.25))
);
driver.start().and(driver.back()).onTrue(

View File

@@ -203,7 +203,14 @@ public class Drivetrain extends SubsystemBase {
* @param pose The pose to which to set the odometry.
*/
public void resetOdometry(Pose2d pose) {
m_estimator.resetPose(
m_estimator.resetPosition(
Rotation2d.fromDegrees(getGyroValue()),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
m_rearLeft.getPosition(),
m_rearRight.getPosition()
},
pose
);
}

View File

@@ -80,6 +80,8 @@ public class Elevator extends SubsystemBase {
maintainPID = new PIDController(ElevatorConstants.kMaintainP, 0, 0);
maintainPID.setTolerance(ElevatorConstants.kAllowedError);
feedForward = new ElevatorFeedforward(
ElevatorConstants.kFeedForwardS,
ElevatorConstants.kFeedForwardG,
@@ -145,27 +147,28 @@ public class Elevator extends SubsystemBase {
public Command maintainPosition() {
return startRun(() -> {
maintainPID.reset();
maintainPID.setSetpoint(pidControllerUp.getSetpoint());
},
() -> {
double maintainOutput = maintainPID.calculate(getEncoderPosition());
if(pidControllerUp.getSetpoint()>encoder.getPosition())
if(!maintainPID.atSetpoint())
elevatorMotor1.setVoltage( MathUtil.clamp(
maintainOutput + feedForward.calculate(0), -1, 1)
maintainOutput + feedForward.calculate(0), -2, 2)
);
else{
elevatorMotor1.setVoltage(
MathUtil.clamp(
maintainOutput + feedForward.calculate(0), -1, 1)
feedForward.calculate(0)
);
}
/*
elevatorMotor1.setVoltage(
feedForward.calculate(0)
);
*/
});

View File

@@ -74,9 +74,9 @@ public class Manipulator extends SubsystemBase {
}).until(() -> !coralBeamBreak.get());
}
public Command retractCommand(DoubleSupplier speed){
public Command retractCommand(DoubleSupplier retractSpeed){
return run(() -> {
manipulatorMotor.set(-speed.getAsDouble());
manipulatorMotor.set(-retractSpeed.getAsDouble());
}
).until(() -> coralBeamBreak.get());
}