|
|
|
|
@@ -199,7 +199,7 @@ public class Drivetrain extends SubsystemBase {
|
|
|
|
|
* @return A complete Command structure that performs the specified action
|
|
|
|
|
*/
|
|
|
|
|
public Command rotateToPose(Pose2d targetPose, boolean rotate180) {
|
|
|
|
|
return lockRotationToSuppliedPose(() -> targetPose, () -> 0, () -> 0, rotate180)
|
|
|
|
|
return lockRotationToSuppliedPose(() -> targetPose, () -> 0, () -> 0, rotate180, false)
|
|
|
|
|
.until(yawRotationController::atSetpoint);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@@ -218,14 +218,16 @@ public class Drivetrain extends SubsystemBase {
|
|
|
|
|
* @param ySpeed The Y (left/right) translational speed of the robot
|
|
|
|
|
* @param rotate180 When false, the front of the robot faces the hub, when true, the back
|
|
|
|
|
* of the robot faces the hub
|
|
|
|
|
* @param lockXWhenStopped When not being commanded to drive, the drivetrain wheels will make an X shape if this is true
|
|
|
|
|
* @return A complete Command structure that performs the specified action
|
|
|
|
|
*/
|
|
|
|
|
public Command lockRotationToHub(DoubleSupplier xSpeed, DoubleSupplier ySpeed, boolean rotate180) {
|
|
|
|
|
public Command lockRotationToHub(DoubleSupplier xSpeed, DoubleSupplier ySpeed, boolean rotate180, boolean lockXWhenStopped) {
|
|
|
|
|
return lockRotationToSuppliedPose(
|
|
|
|
|
Utilities::getHubPose,
|
|
|
|
|
xSpeed,
|
|
|
|
|
ySpeed,
|
|
|
|
|
rotate180
|
|
|
|
|
rotate180,
|
|
|
|
|
lockXWhenStopped
|
|
|
|
|
);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@@ -243,9 +245,10 @@ public class Drivetrain extends SubsystemBase {
|
|
|
|
|
* @param ySpeed The Y (left/right) translational speed of the robot
|
|
|
|
|
* @param rotate180 When false, the front of the robot faces the supplied pose, when true, the back
|
|
|
|
|
* of the robot faces the supplied pose
|
|
|
|
|
* @param lockXWhenStopped When not being commanded to drive, the drivetrain wheels will make an X shape if this is true
|
|
|
|
|
* @return A complete Command structure that performs the specified action
|
|
|
|
|
*/
|
|
|
|
|
public Command lockRotationToSuppliedPose(Supplier<Pose2d> poseSupplier, DoubleSupplier xSpeed, DoubleSupplier ySpeed, boolean rotate180) {
|
|
|
|
|
public Command lockRotationToSuppliedPose(Supplier<Pose2d> poseSupplier, DoubleSupplier xSpeed, DoubleSupplier ySpeed, boolean rotate180, boolean lockXWhenStopped) {
|
|
|
|
|
return runOnce(yawRotationController::reset).andThen(
|
|
|
|
|
drive(
|
|
|
|
|
xSpeed,
|
|
|
|
|
@@ -274,7 +277,8 @@ public class Drivetrain extends SubsystemBase {
|
|
|
|
|
|
|
|
|
|
return outputPower;
|
|
|
|
|
},
|
|
|
|
|
() -> true
|
|
|
|
|
() -> true,
|
|
|
|
|
() -> lockXWhenStopped
|
|
|
|
|
)
|
|
|
|
|
);
|
|
|
|
|
}
|
|
|
|
|
@@ -288,15 +292,17 @@ public class Drivetrain extends SubsystemBase {
|
|
|
|
|
* @param yaw The "yaw" of the tag source relative to the center of the image frame
|
|
|
|
|
* @param xSpeed The X (forward/backward) translational speed of the robot
|
|
|
|
|
* @param ySpeed The Y (left/right) translational speed of the robot
|
|
|
|
|
* @param lockXWhenStopped When not being commanded to drive, the drivetrain wheels will make an X shape if this is true
|
|
|
|
|
* @return A complete Command structure that performs the specified action
|
|
|
|
|
*/
|
|
|
|
|
public Command lockToYaw(DoubleSupplier yaw, DoubleSupplier xSpeed, DoubleSupplier ySpeed) {
|
|
|
|
|
public Command lockToYaw(DoubleSupplier yaw, DoubleSupplier xSpeed, DoubleSupplier ySpeed, boolean lockXWhenStopped) {
|
|
|
|
|
return runOnce(yawRotationController::reset).andThen(
|
|
|
|
|
drive(
|
|
|
|
|
xSpeed,
|
|
|
|
|
ySpeed,
|
|
|
|
|
() -> yawRotationController.calculate(yaw.getAsDouble(), 0),
|
|
|
|
|
() -> true
|
|
|
|
|
() -> true,
|
|
|
|
|
() -> lockXWhenStopped
|
|
|
|
|
)
|
|
|
|
|
);
|
|
|
|
|
}
|
|
|
|
|
@@ -310,14 +316,14 @@ public class Drivetrain extends SubsystemBase {
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public Command drive(DoubleSupplier xSpeed, DoubleSupplier ySpeed, DoubleSupplier rotation, BooleanSupplier fieldRelative) {
|
|
|
|
|
// TODO Specific Alliance code?
|
|
|
|
|
public Command drive(DoubleSupplier xSpeed, DoubleSupplier ySpeed, DoubleSupplier rotation, BooleanSupplier fieldRelative, BooleanSupplier lockXWhenStopped) {
|
|
|
|
|
return run(() -> {
|
|
|
|
|
drive(
|
|
|
|
|
-MathUtil.applyDeadband(xSpeed.getAsDouble(), OIConstants.kDriveDeadband),
|
|
|
|
|
-MathUtil.applyDeadband(ySpeed.getAsDouble(), OIConstants.kDriveDeadband),
|
|
|
|
|
-MathUtil.applyDeadband(rotation.getAsDouble(), OIConstants.kDriveDeadband),
|
|
|
|
|
fieldRelative.getAsBoolean()
|
|
|
|
|
fieldRelative.getAsBoolean(),
|
|
|
|
|
lockXWhenStopped.getAsBoolean()
|
|
|
|
|
);
|
|
|
|
|
});
|
|
|
|
|
}
|
|
|
|
|
@@ -369,30 +375,41 @@ public class Drivetrain extends SubsystemBase {
|
|
|
|
|
);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void drive(double xSpeed, double ySpeed, double rotation, boolean fieldRelative) {
|
|
|
|
|
double p = Math.sqrt(Math.pow(xSpeed, 2) + Math.pow(ySpeed, 2));
|
|
|
|
|
double xSpeedDelivered = 0;
|
|
|
|
|
double ySpeedDelivered = 0;
|
|
|
|
|
public void drive(double xSpeed, double ySpeed, double rotation, boolean fieldRelative, boolean lockXWhenStopped) {
|
|
|
|
|
if(lockXWhenStopped &&
|
|
|
|
|
MathUtil.applyDeadband(xSpeed, OIConstants.kDriveDeadband) == 0 &&
|
|
|
|
|
MathUtil.applyDeadband(ySpeed, OIConstants.kDriveDeadband) == 0 &&
|
|
|
|
|
MathUtil.applyDeadband(rotation, OIConstants.kDriveDeadband) == 0) {
|
|
|
|
|
|
|
|
|
|
if(p != 0){
|
|
|
|
|
xSpeedDelivered = xSpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond;
|
|
|
|
|
ySpeedDelivered = ySpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond;
|
|
|
|
|
}else{
|
|
|
|
|
xSpeedDelivered = 0;
|
|
|
|
|
ySpeedDelivered = 0;
|
|
|
|
|
frontLeft.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(45)));
|
|
|
|
|
frontRight.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(-45)));
|
|
|
|
|
rearLeft.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(-45)));
|
|
|
|
|
rearRight.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(45)));
|
|
|
|
|
} else {
|
|
|
|
|
double p = Math.sqrt(Math.pow(xSpeed, 2) + Math.pow(ySpeed, 2));
|
|
|
|
|
double xSpeedDelivered = 0;
|
|
|
|
|
double ySpeedDelivered = 0;
|
|
|
|
|
|
|
|
|
|
if(p != 0){
|
|
|
|
|
xSpeedDelivered = xSpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond;
|
|
|
|
|
ySpeedDelivered = ySpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond;
|
|
|
|
|
}else{
|
|
|
|
|
xSpeedDelivered = 0;
|
|
|
|
|
ySpeedDelivered = 0;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
double rotationDelivered = rotation * DrivetrainConstants.kMaxAngularSpeed;
|
|
|
|
|
|
|
|
|
|
SwerveModuleState[] swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(
|
|
|
|
|
fieldRelative ?
|
|
|
|
|
ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered,
|
|
|
|
|
//estimator.getEstimatedPosition().getRotation()) :
|
|
|
|
|
Rotation2d.fromDegrees(getGyroValue())) :
|
|
|
|
|
new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered)
|
|
|
|
|
);
|
|
|
|
|
|
|
|
|
|
setModuleStates(swerveModuleStates);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
double rotationDelivered = rotation * DrivetrainConstants.kMaxAngularSpeed;
|
|
|
|
|
|
|
|
|
|
SwerveModuleState[] swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(
|
|
|
|
|
fieldRelative ?
|
|
|
|
|
ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered,
|
|
|
|
|
//estimator.getEstimatedPosition().getRotation()) :
|
|
|
|
|
Rotation2d.fromDegrees(getGyroValue())) :
|
|
|
|
|
new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered)
|
|
|
|
|
);
|
|
|
|
|
|
|
|
|
|
setModuleStates(swerveModuleStates);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void driveWithChassisSpeeds(ChassisSpeeds speeds) {
|
|
|
|
|
|