001/* 002 * Copyright (C) Cross The Road Electronics. All rights reserved. 003 * License information can be found in CTRE_LICENSE.txt 004 * For support and suggestions contact support@ctr-electronics.com or file 005 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases 006 */ 007package com.ctre.phoenix6.mechanisms.swerve; 008 009import static edu.wpi.first.units.Units.Volts; 010 011import com.ctre.phoenix6.StatusCode; 012import com.ctre.phoenix6.controls.VoltageOut; 013import com.ctre.phoenix6.mechanisms.swerve.utility.LegacyPhoenixPIDController; 014 015import edu.wpi.first.math.geometry.Pose2d; 016import edu.wpi.first.math.geometry.Rotation2d; 017import edu.wpi.first.math.geometry.Translation2d; 018import edu.wpi.first.math.kinematics.ChassisSpeeds; 019import edu.wpi.first.math.kinematics.SwerveDriveKinematics; 020import edu.wpi.first.math.kinematics.SwerveModuleState; 021import edu.wpi.first.units.measure.MutVoltage; 022import edu.wpi.first.units.measure.Voltage; 023 024/** 025 * Container for all the Swerve Requests. Use this to find all applicable swerve 026 * drive requests. 027 * <p> 028 * This is also an interface common to all swerve drive control requests that 029 * allow the request to calculate the state to apply to the modules. 030 */ 031public interface LegacySwerveRequest { 032 033 /** 034 * The reference for "forward" is sometimes different if you're talking 035 * about field relative. This addresses which forward to use. 036 */ 037 public enum ForwardReference { 038 /** 039 * This forward reference makes it so "forward" (positive X) is always towards the red alliance. 040 * This is important in situations such as path following where positive X is always towards the 041 * red alliance wall, regardless of where the operator physically are located. 042 */ 043 RedAlliance, 044 /** 045 * This forward references makes it so "forward" (positive X) is determined from the operator's 046 * perspective. This is important for most teleop driven field-centric requests, where positive 047 * X really means to drive away from the operator. 048 * <p> 049 * <b>Important</b>: Users must specify the OperatorPerspective with {@link LegacySwerveDrivetrain} object 050 */ 051 OperatorPerspective 052 } 053 054 /* 055 * Contains everything the control requests need to calculate the module state. 056 */ 057 public class LegacySwerveControlRequestParameters { 058 public double maxSpeedMps; 059 public SwerveDriveKinematics kinematics; 060 public ChassisSpeeds currentChassisSpeed; 061 public Pose2d currentPose; 062 public double timestamp; 063 public Translation2d[] swervePositions; 064 public Rotation2d operatorForwardDirection; 065 public double updatePeriod; 066 } 067 068 /** 069 * Applies this swerve request to the given modules. 070 * This is typically called by the SwerveDrivetrain. 071 * 072 * @param parameters Parameters the control request needs to calculate the module state 073 * @param modulesToApply Modules to which the control request is applied 074 * @return Status code of sending the request 075 */ 076 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply); 077 078 /** 079 * Sets the swerve drive module states to point inward on the 080 * robot in an "X" fashion, creating a natural brake which will 081 * oppose any motion. 082 */ 083 public class SwerveDriveBrake implements LegacySwerveRequest { 084 085 /** 086 * The type of control request to use for the drive motor. 087 */ 088 public LegacySwerveModule.DriveRequestType DriveRequestType = LegacySwerveModule.DriveRequestType.OpenLoopVoltage; 089 /** 090 * The type of control request to use for the steer motor. 091 */ 092 public LegacySwerveModule.SteerRequestType SteerRequestType = LegacySwerveModule.SteerRequestType.MotionMagic; 093 094 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 095 096 for (int i = 0; i < modulesToApply.length; ++i) { 097 SwerveModuleState state = new SwerveModuleState(0, parameters.swervePositions[i].getAngle()); 098 modulesToApply[i].apply(state, DriveRequestType, SteerRequestType); 099 } 100 101 return StatusCode.OK; 102 } 103 104 /** 105 * Sets the type of control request to use for the drive motor. 106 * 107 * @param driveRequestType The type of control request to use for the drive motor 108 * @return this request 109 */ 110 public SwerveDriveBrake withDriveRequestType(LegacySwerveModule.DriveRequestType driveRequestType) { 111 this.DriveRequestType = driveRequestType; 112 return this; 113 } 114 /** 115 * Sets the type of control request to use for the steer motor. 116 * 117 * @param steerRequestType The type of control request to use for the steer motor 118 * @return this request 119 */ 120 public SwerveDriveBrake withSteerRequestType(LegacySwerveModule.SteerRequestType steerRequestType) { 121 this.SteerRequestType = steerRequestType; 122 return this; 123 } 124 } 125 126 /** 127 * Drives the swerve drivetrain in a field-centric manner. 128 * <p> 129 * When users use this request, they specify the direction the robot should 130 * travel oriented against the field, and the rate at which their robot should 131 * rotate about the center of the robot. 132 * <p> 133 * An example scenario is that the robot is oriented to the east, the 134 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. 135 * In this scenario, the robot would drive northward at 5 m/s and turn 136 * counterclockwise at 0.5 rad/s. 137 */ 138 public class FieldCentric implements LegacySwerveRequest { 139 /** 140 * The velocity in the X direction, in m/s. 141 * X is defined as forward according to WPILib convention, 142 * so this determines how fast to travel forward. 143 */ 144 public double VelocityX = 0; 145 /** 146 * The velocity in the Y direction, in m/s. 147 * Y is defined as to the left according to WPILib convention, 148 * so this determines how fast to travel to the left. 149 */ 150 public double VelocityY = 0; 151 /** 152 * The angular rate to rotate at, in radians per second. 153 * Angular rate is defined as counterclockwise positive, 154 * so this determines how fast to turn counterclockwise. 155 */ 156 public double RotationalRate = 0; 157 /** 158 * The allowable deadband of the request. 159 */ 160 public double Deadband = 0; 161 /** 162 * The rotational deadband of the request. 163 */ 164 public double RotationalDeadband = 0; 165 /** 166 * The center of rotation the robot should rotate around. 167 * This is (0,0) by default, which will rotate around the center of the robot. 168 */ 169 public Translation2d CenterOfRotation = new Translation2d(); 170 171 /** 172 * The type of control request to use for the drive motor. 173 */ 174 public LegacySwerveModule.DriveRequestType DriveRequestType = LegacySwerveModule.DriveRequestType.OpenLoopVoltage; 175 /** 176 * The type of control request to use for the steer motor. 177 */ 178 public LegacySwerveModule.SteerRequestType SteerRequestType = LegacySwerveModule.SteerRequestType.MotionMagic; 179 /** 180 * Whether to desaturate wheel speeds before applying. 181 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 182 */ 183 public boolean DesaturateWheelSpeeds = true; 184 185 /** 186 * The perspective to use when determining which direction is forward. 187 */ 188 public ForwardReference ForwardReference = LegacySwerveRequest.ForwardReference.OperatorPerspective; 189 190 /** 191 * The last applied state in case we don't have anything to drive. 192 */ 193 protected SwerveModuleState[] m_lastAppliedState = null; 194 195 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 196 double toApplyX = VelocityX; 197 double toApplyY = VelocityY; 198 if (ForwardReference == LegacySwerveRequest.ForwardReference.OperatorPerspective) { 199 /* If we're operator perspective, modify the X/Y translation by the angle */ 200 Translation2d tmp = new Translation2d(toApplyX, toApplyY); 201 tmp = tmp.rotateBy(parameters.operatorForwardDirection); 202 toApplyX = tmp.getX(); 203 toApplyY = tmp.getY(); 204 } 205 double toApplyOmega = RotationalRate; 206 if (Math.sqrt(toApplyX * toApplyX + toApplyY * toApplyY) < Deadband) { 207 toApplyX = 0; 208 toApplyY = 0; 209 } 210 if (Math.abs(toApplyOmega) < RotationalDeadband) { 211 toApplyOmega = 0; 212 } 213 214 ChassisSpeeds speeds = new ChassisSpeeds(toApplyX, toApplyY, toApplyOmega); 215 speeds.toRobotRelativeSpeeds(parameters.currentPose.getRotation()); 216 speeds.discretize(parameters.updatePeriod); 217 218 var states = parameters.kinematics.toSwerveModuleStates(speeds, CenterOfRotation); 219 if (DesaturateWheelSpeeds && parameters.maxSpeedMps > 0.0) { 220 SwerveDriveKinematics.desaturateWheelSpeeds(states, parameters.maxSpeedMps); 221 } 222 223 for (int i = 0; i < modulesToApply.length; ++i) { 224 modulesToApply[i].apply(states[i], DriveRequestType, SteerRequestType); 225 } 226 227 return StatusCode.OK; 228 } 229 230 /** 231 * Sets the velocity in the X direction, in m/s. 232 * X is defined as forward according to WPILib convention, 233 * so this determines how fast to travel forward. 234 * 235 * @param velocityX Velocity in the X direction, in m/s 236 * @return this request 237 */ 238 public FieldCentric withVelocityX(double velocityX) { 239 this.VelocityX = velocityX; 240 return this; 241 } 242 243 /** 244 * Sets the velocity in the Y direction, in m/s. 245 * Y is defined as to the left according to WPILib convention, 246 * so this determines how fast to travel to the left. 247 * 248 * @param velocityY Velocity in the Y direction, in m/s 249 * @return this request 250 */ 251 public FieldCentric withVelocityY(double velocityY) { 252 this.VelocityY = velocityY; 253 return this; 254 } 255 256 /** 257 * The angular rate to rotate at, in radians per second. 258 * Angular rate is defined as counterclockwise positive, 259 * so this determines how fast to turn counterclockwise. 260 * 261 * @param rotationalRate Angular rate to rotate at, in radians per second 262 * @return this request 263 */ 264 public FieldCentric withRotationalRate(double rotationalRate) { 265 this.RotationalRate = rotationalRate; 266 return this; 267 } 268 269 /** 270 * Sets the allowable deadband of the request. 271 * 272 * @param deadband Allowable deadband of the request 273 * @return this request 274 */ 275 public FieldCentric withDeadband(double deadband) { 276 this.Deadband = deadband; 277 return this; 278 } 279 /** 280 * Sets the rotational deadband of the request. 281 * 282 * @param rotationalDeadband Rotational deadband of the request 283 * @return this request 284 */ 285 public FieldCentric withRotationalDeadband(double rotationalDeadband) { 286 this.RotationalDeadband = rotationalDeadband; 287 return this; 288 } 289 /** 290 * Sets the center of rotation of the request 291 * 292 * @param centerOfRotation The center of rotation the robot should rotate around. 293 * @return this request 294 */ 295 public FieldCentric withCenterOfRotation(Translation2d centerOfRotation) { 296 this.CenterOfRotation = centerOfRotation; 297 return this; 298 } 299 300 /** 301 * Sets the type of control request to use for the drive motor. 302 * 303 * @param driveRequestType The type of control request to use for the drive motor 304 * @return this request 305 */ 306 public FieldCentric withDriveRequestType(LegacySwerveModule.DriveRequestType driveRequestType) { 307 this.DriveRequestType = driveRequestType; 308 return this; 309 } 310 /** 311 * Sets the type of control request to use for the steer motor. 312 * 313 * @param steerRequestType The type of control request to use for the steer motor 314 * @return this request 315 */ 316 public FieldCentric withSteerRequestType(LegacySwerveModule.SteerRequestType steerRequestType) { 317 this.SteerRequestType = steerRequestType; 318 return this; 319 } 320 321 /** 322 * Sets whether to desaturate wheel speeds before applying. 323 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 324 * 325 * @param desaturateWheelSpeeds Whether to desaturate wheel speeds 326 * @return this request 327 */ 328 public FieldCentric withDesaturateWheelSpeeds(boolean desaturateWheelSpeeds) { 329 this.DesaturateWheelSpeeds = desaturateWheelSpeeds; 330 return this; 331 } 332 } 333 334 /** 335 * Drives the swerve drivetrain in a field-centric manner, maintaining a 336 * specified heading angle to ensure the robot is facing the desired direction 337 * <p> 338 * When users use this request, they specify the direction the robot should 339 * travel oriented against the field, and the direction the robot should be facing. 340 * <p> 341 * An example scenario is that the robot is oriented to the east, the VelocityX 342 * is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees. 343 * In this scenario, the robot would drive northward at 5 m/s and turn clockwise 344 * to a target of 180 degrees. 345 * <p> 346 * This control request is especially useful for autonomous control, where the 347 * robot should be facing a changing direction throughout the motion. 348 */ 349 public class FieldCentricFacingAngle implements LegacySwerveRequest { 350 /** 351 * The velocity in the X direction, in m/s. 352 * X is defined as forward according to WPILib convention, 353 * so this determines how fast to travel forward. 354 */ 355 public double VelocityX = 0; 356 /** 357 * The velocity in the Y direction, in m/s. 358 * Y is defined as to the left according to WPILib convention, 359 * so this determines how fast to travel to the left. 360 */ 361 public double VelocityY = 0; 362 /** 363 * The desired direction to face. 364 * 0 Degrees is defined as in the direction of the X axis. 365 * As a result, a TargetDirection of 90 degrees will point along 366 * the Y axis, or to the left. 367 */ 368 public Rotation2d TargetDirection = new Rotation2d(); 369 370 /** 371 * The allowable deadband of the request. 372 */ 373 public double Deadband = 0; 374 /** 375 * The rotational deadband of the request. 376 */ 377 public double RotationalDeadband = 0; 378 /** 379 * The center of rotation the robot should rotate around. 380 * This is (0,0) by default, which will rotate around the center of the robot. 381 */ 382 public Translation2d CenterOfRotation = new Translation2d(); 383 384 /** 385 * The type of control request to use for the drive motor. 386 */ 387 public LegacySwerveModule.DriveRequestType DriveRequestType = LegacySwerveModule.DriveRequestType.OpenLoopVoltage; 388 /** 389 * The type of control request to use for the steer motor. 390 */ 391 public LegacySwerveModule.SteerRequestType SteerRequestType = LegacySwerveModule.SteerRequestType.MotionMagic; 392 /** 393 * Whether to desaturate wheel speeds before applying. 394 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 395 */ 396 public boolean DesaturateWheelSpeeds = true; 397 398 /** 399 * The PID controller used to maintain the desired heading. 400 * Users can specify the PID gains to change how aggressively to maintain 401 * heading. 402 * <p> 403 * This PID controller operates on heading radians and outputs a target 404 * rotational rate in radians per second. 405 */ 406 public LegacyPhoenixPIDController HeadingController = new LegacyPhoenixPIDController(0, 0, 0); 407 408 /** 409 * The perspective to use when determining which direction is forward. 410 */ 411 public ForwardReference ForwardReference = LegacySwerveRequest.ForwardReference.OperatorPerspective; 412 413 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 414 double toApplyX = VelocityX; 415 double toApplyY = VelocityY; 416 Rotation2d angleToFace = TargetDirection; 417 if (ForwardReference == LegacySwerveRequest.ForwardReference.OperatorPerspective) { 418 /* If we're operator perspective, modify the X/Y translation by the angle */ 419 Translation2d tmp = new Translation2d(toApplyX, toApplyY); 420 tmp = tmp.rotateBy(parameters.operatorForwardDirection); 421 toApplyX = tmp.getX(); 422 toApplyY = tmp.getY(); 423 /* And rotate the direction we want to face by the angle */ 424 angleToFace = angleToFace.rotateBy(parameters.operatorForwardDirection); 425 } 426 427 double rotationRate = HeadingController.calculate(parameters.currentPose.getRotation().getRadians(), 428 angleToFace.getRadians(), parameters.timestamp); 429 430 double toApplyOmega = rotationRate; 431 if (Math.sqrt(toApplyX * toApplyX + toApplyY * toApplyY) < Deadband) { 432 toApplyX = 0; 433 toApplyY = 0; 434 } 435 if (Math.abs(toApplyOmega) < RotationalDeadband) { 436 toApplyOmega = 0; 437 } 438 439 ChassisSpeeds speeds = new ChassisSpeeds(toApplyX, toApplyY, toApplyOmega); 440 speeds.toRobotRelativeSpeeds(parameters.currentPose.getRotation()); 441 speeds.discretize(parameters.updatePeriod); 442 443 var states = parameters.kinematics.toSwerveModuleStates(speeds, CenterOfRotation); 444 if (DesaturateWheelSpeeds && parameters.maxSpeedMps > 0.0) { 445 SwerveDriveKinematics.desaturateWheelSpeeds(states, parameters.maxSpeedMps); 446 } 447 448 for (int i = 0; i < modulesToApply.length; ++i) { 449 modulesToApply[i].apply(states[i], DriveRequestType, SteerRequestType); 450 } 451 452 return StatusCode.OK; 453 } 454 455 /** 456 * Sets the velocity in the X direction, in m/s. 457 * X is defined as forward according to WPILib convention, 458 * so this determines how fast to travel forward. 459 * 460 * @param velocityX Velocity in the X direction, in m/s 461 * @return this request 462 */ 463 public FieldCentricFacingAngle withVelocityX(double velocityX) { 464 this.VelocityX = velocityX; 465 return this; 466 } 467 468 /** 469 * Sets the velocity in the Y direction, in m/s. 470 * Y is defined as to the left according to WPILib convention, 471 * so this determines how fast to travel to the left. 472 * 473 * @param velocityY Velocity in the Y direction, in m/s 474 * @return this request 475 */ 476 public FieldCentricFacingAngle withVelocityY(double velocityY) { 477 this.VelocityY = velocityY; 478 return this; 479 } 480 481 /** 482 * Sets the desired direction to face. 483 * 0 Degrees is defined as in the direction of the X axis. 484 * As a result, a TargetDirection of 90 degrees will point along 485 * the Y axis, or to the left. 486 * 487 * @param targetDirection Desired direction to face 488 * @return this request 489 */ 490 public FieldCentricFacingAngle withTargetDirection(Rotation2d targetDirection) { 491 this.TargetDirection = targetDirection; 492 return this; 493 } 494 495 /** 496 * Sets the allowable deadband of the request. 497 * 498 * @param deadband Allowable deadband of the request 499 * @return this request 500 */ 501 public FieldCentricFacingAngle withDeadband(double deadband) { 502 this.Deadband = deadband; 503 return this; 504 } 505 /** 506 * Sets the rotational deadband of the request. 507 * 508 * @param rotationalDeadband Rotational deadband of the request 509 * @return this request 510 */ 511 public FieldCentricFacingAngle withRotationalDeadband(double rotationalDeadband) { 512 this.RotationalDeadband = rotationalDeadband; 513 return this; 514 } 515 /** 516 * Sets the center of rotation of the request 517 * 518 * @param centerOfRotation The center of rotation the robot should rotate around. 519 * @return this request 520 */ 521 public FieldCentricFacingAngle withCenterOfRotation(Translation2d centerOfRotation) { 522 this.CenterOfRotation = centerOfRotation; 523 return this; 524 } 525 526 /** 527 * Sets the type of control request to use for the drive motor. 528 * 529 * @param driveRequestType The type of control request to use for the drive motor 530 * @return this request 531 */ 532 public FieldCentricFacingAngle withDriveRequestType(LegacySwerveModule.DriveRequestType driveRequestType) { 533 this.DriveRequestType = driveRequestType; 534 return this; 535 } 536 /** 537 * Sets the type of control request to use for the steer motor. 538 * 539 * @param steerRequestType The type of control request to use for the steer motor 540 * @return this request 541 */ 542 public FieldCentricFacingAngle withSteerRequestType(LegacySwerveModule.SteerRequestType steerRequestType) { 543 this.SteerRequestType = steerRequestType; 544 return this; 545 } 546 547 /** 548 * Sets whether to desaturate wheel speeds before applying. 549 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 550 * 551 * @param desaturateWheelSpeeds Whether to desaturate wheel speeds 552 * @return this request 553 */ 554 public FieldCentricFacingAngle withDesaturateWheelSpeeds(boolean desaturateWheelSpeeds) { 555 this.DesaturateWheelSpeeds = desaturateWheelSpeeds; 556 return this; 557 } 558 } 559 560 /** 561 * Does nothing to the swerve module state. This is the default state of a newly 562 * created swerve drive mechanism. 563 */ 564 public class Idle implements LegacySwerveRequest { 565 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 566 return StatusCode.OK; 567 } 568 } 569 570 /** 571 * Sets the swerve drive modules to point to a specified direction. 572 */ 573 public class PointWheelsAt implements LegacySwerveRequest { 574 575 /** 576 * The direction to point the modules toward. 577 * This direction is still optimized to what the module was previously at. 578 */ 579 public Rotation2d ModuleDirection = new Rotation2d(); 580 /** 581 * The type of control request to use for the drive motor. 582 */ 583 public LegacySwerveModule.DriveRequestType DriveRequestType = LegacySwerveModule.DriveRequestType.OpenLoopVoltage; 584 /** 585 * The type of control request to use for the steer motor. 586 */ 587 public LegacySwerveModule.SteerRequestType SteerRequestType = LegacySwerveModule.SteerRequestType.MotionMagic; 588 589 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 590 591 for (int i = 0; i < modulesToApply.length; ++i) { 592 SwerveModuleState state = new SwerveModuleState(0, ModuleDirection); 593 modulesToApply[i].apply(state, DriveRequestType, SteerRequestType); 594 } 595 596 return StatusCode.OK; 597 } 598 599 /** 600 * Sets the direction to point the modules toward. 601 * This direction is still optimized to what the module was previously at. 602 * 603 * @param moduleDirection Direction to point the modules toward 604 * @return this request 605 */ 606 public PointWheelsAt withModuleDirection(Rotation2d moduleDirection) { 607 this.ModuleDirection = moduleDirection; 608 return this; 609 } 610 611 /** 612 * Sets the type of control request to use for the drive motor. 613 * 614 * @param driveRequestType The type of control request to use for the drive motor 615 * @return this request 616 */ 617 public PointWheelsAt withDriveRequestType(LegacySwerveModule.DriveRequestType driveRequestType) { 618 this.DriveRequestType = driveRequestType; 619 return this; 620 } 621 /** 622 * Sets the type of control request to use for the steer motor. 623 * 624 * @param steerRequestType The type of control request to use for the steer motor 625 * @return this request 626 */ 627 public PointWheelsAt withSteerRequestType(LegacySwerveModule.SteerRequestType steerRequestType) { 628 this.SteerRequestType = steerRequestType; 629 return this; 630 } 631 } 632 633 /** 634 * Drives the swerve drivetrain in a robot-centric manner. 635 * <p> 636 * When users use this request, they specify the direction the robot should 637 * travel oriented against the robot itself, and the rate at which their 638 * robot should rotate about the center of the robot. 639 * <p> 640 * An example scenario is that the robot is oriented to the east, the 641 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. 642 * In this scenario, the robot would drive eastward at 5 m/s and turn 643 * counterclockwise at 0.5 rad/s. 644 */ 645 public class RobotCentric implements LegacySwerveRequest { 646 /** 647 * The velocity in the X direction, in m/s. 648 * X is defined as forward according to WPILib convention, 649 * so this determines how fast to travel forward. 650 */ 651 public double VelocityX = 0; 652 /** 653 * The velocity in the Y direction, in m/s. 654 * Y is defined as to the left according to WPILib convention, 655 * so this determines how fast to travel to the left. 656 */ 657 public double VelocityY = 0; 658 /** 659 * The angular rate to rotate at, in radians per second. 660 * Angular rate is defined as counterclockwise positive, 661 * so this determines how fast to turn counterclockwise. 662 */ 663 public double RotationalRate = 0; 664 665 /** 666 * The allowable deadband of the request. 667 */ 668 public double Deadband = 0; 669 /** 670 * The rotational deadband of the request. 671 */ 672 public double RotationalDeadband = 0; 673 /** 674 * The center of rotation the robot should rotate around. 675 * This is (0,0) by default, which will rotate around the center of the robot. 676 */ 677 public Translation2d CenterOfRotation = new Translation2d(); 678 679 /** 680 * The type of control request to use for the drive motor. 681 */ 682 public LegacySwerveModule.DriveRequestType DriveRequestType = LegacySwerveModule.DriveRequestType.OpenLoopVoltage; 683 /** 684 * The type of control request to use for the steer motor. 685 */ 686 public LegacySwerveModule.SteerRequestType SteerRequestType = LegacySwerveModule.SteerRequestType.MotionMagic; 687 /** 688 * Whether to desaturate wheel speeds before applying. 689 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 690 */ 691 public boolean DesaturateWheelSpeeds = true; 692 693 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 694 double toApplyX = VelocityX; 695 double toApplyY = VelocityY; 696 double toApplyOmega = RotationalRate; 697 if (Math.sqrt(toApplyX * toApplyX + toApplyY * toApplyY) < Deadband) { 698 toApplyX = 0; 699 toApplyY = 0; 700 } 701 if (Math.abs(toApplyOmega) < RotationalDeadband) { 702 toApplyOmega = 0; 703 } 704 ChassisSpeeds speeds = new ChassisSpeeds(toApplyX, toApplyY, toApplyOmega); 705 706 var states = parameters.kinematics.toSwerveModuleStates(speeds, CenterOfRotation); 707 if (DesaturateWheelSpeeds && parameters.maxSpeedMps > 0.0) { 708 SwerveDriveKinematics.desaturateWheelSpeeds(states, parameters.maxSpeedMps); 709 } 710 711 for (int i = 0; i < modulesToApply.length; ++i) { 712 modulesToApply[i].apply(states[i], DriveRequestType, SteerRequestType); 713 } 714 715 return StatusCode.OK; 716 } 717 718 /** 719 * Sets the velocity in the X direction, in m/s. 720 * X is defined as forward according to WPILib convention, 721 * so this determines how fast to travel forward. 722 * 723 * @param velocityX Velocity in the X direction, in m/s 724 * @return this request 725 */ 726 public RobotCentric withVelocityX(double velocityX) { 727 this.VelocityX = velocityX; 728 return this; 729 } 730 731 /** 732 * Sets the velocity in the Y direction, in m/s. 733 * Y is defined as to the left according to WPILib convention, 734 * so this determines how fast to travel to the left. 735 * 736 * @param velocityY Velocity in the Y direction, in m/s 737 * @return this request 738 */ 739 public RobotCentric withVelocityY(double velocityY) { 740 this.VelocityY = velocityY; 741 return this; 742 } 743 744 /** 745 * The angular rate to rotate at, in radians per second. 746 * Angular rate is defined as counterclockwise positive, 747 * so this determines how fast to turn counterclockwise. 748 * 749 * @param rotationalRate Angular rate to rotate at, in radians per second 750 * @return this request 751 */ 752 public RobotCentric withRotationalRate(double rotationalRate) { 753 this.RotationalRate = rotationalRate; 754 return this; 755 } 756 757 /** 758 * Sets the allowable deadband of the request. 759 * 760 * @param deadband Allowable deadband of the request 761 * @return this request 762 */ 763 public RobotCentric withDeadband(double deadband) { 764 this.Deadband = deadband; 765 return this; 766 } 767 /** 768 * Sets the rotational deadband of the request. 769 * 770 * @param rotationalDeadband Rotational deadband of the request 771 * @return this request 772 */ 773 public RobotCentric withRotationalDeadband(double rotationalDeadband) { 774 this.RotationalDeadband = rotationalDeadband; 775 return this; 776 } 777 /** 778 * Sets the center of rotation of the request 779 * 780 * @param centerOfRotation The center of rotation the robot should rotate around. 781 * @return this request 782 */ 783 public RobotCentric withCenterOfRotation(Translation2d centerOfRotation) { 784 this.CenterOfRotation = centerOfRotation; 785 return this; 786 } 787 788 /** 789 * Sets the type of control request to use for the drive motor. 790 * 791 * @param driveRequestType The type of control request to use for the drive motor 792 * @return this request 793 */ 794 public RobotCentric withDriveRequestType(LegacySwerveModule.DriveRequestType driveRequestType) { 795 this.DriveRequestType = driveRequestType; 796 return this; 797 } 798 /** 799 * Sets the type of control request to use for the steer motor. 800 * 801 * @param steerRequestType The type of control request to use for the steer motor 802 * @return this request 803 */ 804 public RobotCentric withSteerRequestType(LegacySwerveModule.SteerRequestType steerRequestType) { 805 this.SteerRequestType = steerRequestType; 806 return this; 807 } 808 809 /** 810 * Sets whether to desaturate wheel speeds before applying. 811 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 812 * 813 * @param desaturateWheelSpeeds Whether to desaturate wheel speeds 814 * @return this request 815 */ 816 public RobotCentric withDesaturateWheelSpeeds(boolean desaturateWheelSpeeds) { 817 this.DesaturateWheelSpeeds = desaturateWheelSpeeds; 818 return this; 819 } 820 } 821 822 /** 823 * Accepts a generic ChassisSpeeds to apply to the drivetrain. 824 */ 825 public class ApplyChassisSpeeds implements LegacySwerveRequest { 826 827 /** 828 * The chassis speeds to apply to the drivetrain. 829 */ 830 public ChassisSpeeds Speeds = new ChassisSpeeds(); 831 /** 832 * The center of rotation to rotate around. 833 */ 834 public Translation2d CenterOfRotation = new Translation2d(0, 0); 835 /** 836 * The type of control request to use for the drive motor. 837 */ 838 public LegacySwerveModule.DriveRequestType DriveRequestType = LegacySwerveModule.DriveRequestType.OpenLoopVoltage; 839 /** 840 * The type of control request to use for the steer motor. 841 */ 842 public LegacySwerveModule.SteerRequestType SteerRequestType = LegacySwerveModule.SteerRequestType.MotionMagic; 843 /** 844 * Whether to desaturate wheel speeds before applying. 845 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 846 */ 847 public boolean DesaturateWheelSpeeds = true; 848 849 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 850 var states = parameters.kinematics.toSwerveModuleStates(Speeds, CenterOfRotation); 851 if (DesaturateWheelSpeeds && parameters.maxSpeedMps > 0.0) { 852 SwerveDriveKinematics.desaturateWheelSpeeds(states, parameters.maxSpeedMps); 853 } 854 855 for (int i = 0; i < modulesToApply.length; ++i) { 856 modulesToApply[i].apply(states[i], DriveRequestType, SteerRequestType); 857 } 858 859 return StatusCode.OK; 860 } 861 862 /** 863 * Sets the chassis speeds to apply to the drivetrain. 864 * 865 * @param speeds Chassis speeds to apply to the drivetrain 866 * @return this request 867 */ 868 public ApplyChassisSpeeds withSpeeds(ChassisSpeeds speeds) { 869 this.Speeds = speeds; 870 return this; 871 } 872 /** 873 * Sets the center of rotation to rotate around. 874 * 875 * @param centerOfRotation Center of rotation to rotate around 876 * @return this request 877 */ 878 public ApplyChassisSpeeds withCenterOfRotation(Translation2d centerOfRotation) { 879 this.CenterOfRotation = centerOfRotation; 880 return this; 881 } 882 883 /** 884 * Sets the type of control request to use for the drive motor. 885 * 886 * @param driveRequestType The type of control request to use for the drive motor 887 * @return this request 888 */ 889 public ApplyChassisSpeeds withDriveRequestType(LegacySwerveModule.DriveRequestType driveRequestType) { 890 this.DriveRequestType = driveRequestType; 891 return this; 892 } 893 /** 894 * Sets the type of control request to use for the steer motor. 895 * 896 * @param steerRequestType The type of control request to use for the steer motor 897 * @return this request 898 */ 899 public ApplyChassisSpeeds withSteerRequestType(LegacySwerveModule.SteerRequestType steerRequestType) { 900 this.SteerRequestType = steerRequestType; 901 return this; 902 } 903 904 /** 905 * Sets whether to desaturate wheel speeds before applying. 906 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 907 * 908 * @param desaturateWheelSpeeds Whether to desaturate wheel speeds 909 * @return this request 910 */ 911 public ApplyChassisSpeeds withDesaturateWheelSpeeds(boolean desaturateWheelSpeeds) { 912 this.DesaturateWheelSpeeds = desaturateWheelSpeeds; 913 return this; 914 } 915 } 916 917 /** 918 * SysId-specific SwerveRequest to characterize the translational 919 * characteristics of a swerve drivetrain. 920 */ 921 public class SysIdSwerveTranslation implements LegacySwerveRequest { 922 /** 923 * Voltage to apply to drive wheels. This is final to enforce mutating the value. 924 */ 925 public final MutVoltage VoltsToApply = Volts.mutable(0); 926 927 /* Local reference to a voltage request to drive the motors with */ 928 private VoltageOut m_voltRequest = new VoltageOut(0); 929 930 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 931 for (int i = 0; i < modulesToApply.length; ++i) { 932 modulesToApply[i].applyCharacterization(Rotation2d.fromDegrees(0), m_voltRequest.withOutput(VoltsToApply.in(Volts))); 933 } 934 return StatusCode.OK; 935 } 936 937 /** 938 * Sets the voltage to apply to the drive wheels. 939 * 940 * @param volts Voltage to apply 941 * @return this request 942 */ 943 public SysIdSwerveTranslation withVolts(Voltage volts) { 944 VoltsToApply.mut_replace(volts); 945 return this; 946 } 947 } 948 949 /** 950 * SysId-specific SwerveRequest to characterize the rotational 951 * characteristics of a swerve drivetrain. 952 */ 953 public class SysIdSwerveRotation implements LegacySwerveRequest { 954 /** 955 * Voltage to apply to drive wheels. This is final to enforce mutating the value. 956 */ 957 public final MutVoltage VoltsToApply = Volts.mutable(0); 958 959 /* Local reference to a voltage request to drive the motors with */ 960 private VoltageOut m_voltRequest = new VoltageOut(0); 961 962 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 963 for (int i = 0; i < modulesToApply.length; ++i) { 964 modulesToApply[i].applyCharacterization(parameters.swervePositions[i].getAngle().plus(Rotation2d.fromDegrees(90)), 965 m_voltRequest.withOutput(VoltsToApply.in(Volts))); 966 } 967 return StatusCode.OK; 968 } 969 970 /** 971 * Update the voltage to apply to the drive wheels. 972 * 973 * @param volts Voltage to apply 974 * @return this request 975 */ 976 public SysIdSwerveRotation withVolts(Voltage volts) { 977 VoltsToApply.mut_replace(volts); 978 return this; 979 } 980 } 981 982 /** 983 * SysId-specific SwerveRequest to characterize the steer module 984 * characteristics of a swerve drivetrain. 985 */ 986 public class SysIdSwerveSteerGains implements LegacySwerveRequest { 987 /** 988 * Voltage to apply to steer motors. This is final to enforce mutating the value. 989 */ 990 public final MutVoltage VoltsToApply = Volts.mutable(0); 991 992 /* Local reference to a voltage request to drive the motors with */ 993 private VoltageOut m_voltRequest = new VoltageOut(0); 994 995 public StatusCode apply(LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) { 996 for (int i = 0; i < modulesToApply.length; ++i) { 997 modulesToApply[i].getSteerMotor().setControl(m_voltRequest.withOutput(VoltsToApply.in(Volts))); 998 modulesToApply[i].getDriveMotor().setControl(m_voltRequest.withOutput(0)); 999 } 1000 return StatusCode.OK; 1001 } 1002 1003 /** 1004 * Sets the voltage to apply to the steer motors. 1005 * 1006 * @param volts Voltage to apply 1007 * @return this request 1008 */ 1009 public SysIdSwerveSteerGains withVolts(Voltage volts) { 1010 VoltsToApply.mut_replace(volts); 1011 return this; 1012 } 1013 } 1014}