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.swerve; 008 009import static edu.wpi.first.units.Units.*; 010 011import java.util.HashMap; 012 013import com.ctre.phoenix6.StatusCode; 014import com.ctre.phoenix6.controls.CoastOut; 015import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC; 016import com.ctre.phoenix6.controls.PositionVoltage; 017import com.ctre.phoenix6.controls.VoltageOut; 018import com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveControlParameters; 019import com.ctre.phoenix6.swerve.jni.SwerveJNI; 020import com.ctre.phoenix6.swerve.utility.PhoenixPIDController; 021 022import edu.wpi.first.math.geometry.Rotation2d; 023import edu.wpi.first.math.geometry.Translation2d; 024import edu.wpi.first.math.kinematics.ChassisSpeeds; 025import edu.wpi.first.math.kinematics.SwerveDriveKinematics; 026import edu.wpi.first.units.measure.*; 027 028/** 029 * Container for all the Swerve Requests. Use this to find all applicable swerve 030 * drive requests. 031 * <p> 032 * This is also an interface common to all swerve drive control requests that 033 * allow the request to calculate the state to apply to the modules. 034 */ 035public interface SwerveRequest { 036 /** 037 * In field-centric control, the direction of "forward" is sometimes different 038 * depending on perspective. This addresses which forward to use. 039 */ 040 public enum ForwardPerspectiveValue { 041 /** 042 * "Forward" (positive X) is determined from the operator's perspective. This 043 * is important for most teleop driven field-centric requests, where positive 044 * X means to drive away from the operator. 045 * <p> 046 * Important: Users must specify the OperatorPerspective in the SwerveDrivetrain object 047 */ 048 OperatorPerspective(0), 049 /** 050 * "Forward" (positive X) is always from the perspective of the blue alliance (i.e. towards 051 * the red alliance). This is important in situations such as path following where positive 052 * X is always from the blue alliance perspective, regardless of where the operator is 053 * physically located. 054 */ 055 BlueAlliance(1); 056 057 public final int value; 058 059 ForwardPerspectiveValue(int initValue) { 060 this.value = initValue; 061 } 062 063 private static HashMap<Integer, ForwardPerspectiveValue> _map = null; 064 static { 065 _map = new HashMap<Integer, ForwardPerspectiveValue>(); 066 for (ForwardPerspectiveValue type : ForwardPerspectiveValue.values()) { 067 _map.put(type.value, type); 068 } 069 } 070 071 /** 072 * Gets ForwardPerspectiveValue from specified value 073 * 074 * @param value Value of ForwardPerspectiveValue 075 * @return ForwardPerspectiveValue of specified value 076 */ 077 public static ForwardPerspectiveValue valueOf(int value) { 078 ForwardPerspectiveValue retval = _map.get(value); 079 if (retval != null) 080 return retval; 081 return ForwardPerspectiveValue.values()[0]; 082 } 083 } 084 085 /** 086 * In field-centric control, the direction of "forward" for the target direction sometimes 087 * differs from "forward" for translation. This addresses which forward to use. 088 */ 089 public enum TargetDirectionPerspectiveValue { 090 /** 091 * Match the ForwardPerspective parameter for heading control. 092 */ 093 UseForwardPerspective(0), 094 /** 095 * "Forward" (0 deg) is always from the perspective of the blue alliance (i.e. 096 * towards the red alliance). This can be used to allow for the robot rotation to track 097 * vision targets while using operator-perspective joystick control for translation. 098 */ 099 BlueAlliance(1); 100 101 public final int value; 102 103 TargetDirectionPerspectiveValue(int initValue) { 104 this.value = initValue; 105 } 106 107 private static HashMap<Integer, TargetDirectionPerspectiveValue> _map = null; 108 static { 109 _map = new HashMap<Integer, TargetDirectionPerspectiveValue>(); 110 for (TargetDirectionPerspectiveValue type : TargetDirectionPerspectiveValue.values()) { 111 _map.put(type.value, type); 112 } 113 } 114 115 /** 116 * Gets TargetDirectionPerspectiveValue from specified value 117 * 118 * @param value Value of TargetDirectionPerspectiveValue 119 * @return TargetDirectionPerspectiveValue of specified value 120 */ 121 public static TargetDirectionPerspectiveValue valueOf(int value) { 122 TargetDirectionPerspectiveValue retval = _map.get(value); 123 if (retval != null) 124 return retval; 125 return TargetDirectionPerspectiveValue.values()[0]; 126 } 127 } 128 129 /** 130 * Applies this swerve request to the given modules. This is 131 * typically called by the SwerveDrivetrain odometry thread. 132 * <p> 133 * For native swerve requests, this API can be called from a 134 * non-native request's {@code apply} to compose the two together. 135 * 136 * @param parameters Parameters the control request needs to calculate the module state 137 * @param modulesToApply Modules to which the control request is applied 138 * @return Status code of sending the request 139 */ 140 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply); 141 142 /** Swerve requests implemented in native code. */ 143 public interface NativeSwerveRequest extends SwerveRequest { 144 /** 145 * Applies a native swerve request to the native drivetrain with the provided ID. 146 * <p> 147 * When this is implemented, the regular {@link #apply} function should do nothing 148 * (return OK). Additionally, this cannot be called from another swerve request's 149 * apply method, as this overrides the native swerve request of the drivetrain. 150 * <p> 151 * Unlike {@link #apply}, this function is called every time {@link SwerveDrivetrain#setControl} 152 * is run, not every loop of the odometry thread. Instead, the underlying native 153 * request is run at the full update frequency of the odometry thread. 154 * 155 * @param id ID of the native swerve drivetrain 156 */ 157 public void applyNative(int id); 158 } 159 160 161 /** 162 * Does nothing to the swerve module state. This is the default state of a newly 163 * created swerve drive mechanism. 164 */ 165 public static class Idle implements NativeSwerveRequest { 166 167 168 169 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 170 return StatusCode.valueOf(SwerveJNI.JNI_Request_Apply_Idle(parameters.drivetrainId)); 171 } 172 173 public void applyNative(int id) { 174 SwerveJNI.JNI_SetControl_Idle(id); 175 } 176 } 177 178 /** 179 * Sets the swerve drive module states to point inward on the robot in an "X" 180 * fashion, creating a natural brake which will oppose any motion. 181 */ 182 public static class SwerveDriveBrake implements NativeSwerveRequest { 183 /** 184 * The type of control request to use for the drive motor. 185 */ 186 public SwerveModule.DriveRequestType DriveRequestType = SwerveModule.DriveRequestType.OpenLoopVoltage; 187 /** 188 * The type of control request to use for the drive motor. 189 */ 190 public SwerveModule.SteerRequestType SteerRequestType = SwerveModule.SteerRequestType.Position; 191 192 /** 193 * Modifies the DriveRequestType parameter and returns itself. 194 * <p> 195 * The type of control request to use for the drive motor. 196 * 197 * @param newDriveRequestType Parameter to modify 198 * @return this object 199 */ 200 public SwerveDriveBrake withDriveRequestType(SwerveModule.DriveRequestType newDriveRequestType) { 201 this.DriveRequestType = newDriveRequestType; 202 return this; 203 } 204 205 /** 206 * Modifies the SteerRequestType parameter and returns itself. 207 * <p> 208 * The type of control request to use for the drive motor. 209 * 210 * @param newSteerRequestType Parameter to modify 211 * @return this object 212 */ 213 public SwerveDriveBrake withSteerRequestType(SwerveModule.SteerRequestType newSteerRequestType) { 214 this.SteerRequestType = newSteerRequestType; 215 return this; 216 } 217 218 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 219 return StatusCode.valueOf(SwerveJNI.JNI_Request_Apply_SwerveDriveBrake(parameters.drivetrainId, 220 DriveRequestType.value, 221 SteerRequestType.value)); 222 } 223 224 public void applyNative(int id) { 225 SwerveJNI.JNI_SetControl_SwerveDriveBrake(id, 226 DriveRequestType.value, 227 SteerRequestType.value); 228 } 229 } 230 231 /** 232 * Drives the swerve drivetrain in a field-centric manner. This request is 233 * optimized for joystick control during teleop with built-in deadbands. 234 * <p> 235 * This request specifies the direction the robot should travel oriented against 236 * the field, and the rate at which their robot should rotate about the center 237 * of the robot. 238 * <p> 239 * An example scenario is that the robot is oriented to the field +Y (left), the 240 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. In 241 * this scenario, the robot would drive along the field +X (forward) at 5 m/s 242 * and turn counterclockwise at 0.5 rad/s. 243 */ 244 public static class FieldCentric implements NativeSwerveRequest { 245 /** 246 * The velocity in the X direction, in m/s. X is defined as forward according to 247 * WPILib convention, so this determines how fast to travel forward. 248 */ 249 public double VelocityX = 0; 250 /** 251 * The velocity in the Y direction, in m/s. Y is defined as to the left 252 * according to WPILib convention, so this determines how fast to travel to the 253 * left. 254 */ 255 public double VelocityY = 0; 256 /** 257 * The angular rate to rotate at, in radians per second. Angular rate is defined 258 * as counterclockwise positive, so this determines how fast to turn 259 * counterclockwise. 260 */ 261 public double RotationalRate = 0; 262 /** 263 * The allowable deadband of the request, in m/s. 264 */ 265 public double Deadband = 0; 266 /** 267 * The rotational deadband of the request, in radians per second. 268 */ 269 public double RotationalDeadband = 0; 270 /** 271 * The center of rotation the robot should rotate around. This is (0,0) by 272 * default, which will rotate around the center of the robot. 273 */ 274 public Translation2d CenterOfRotation = new Translation2d(); 275 /** 276 * The type of control request to use for the drive motor. 277 */ 278 public SwerveModule.DriveRequestType DriveRequestType = SwerveModule.DriveRequestType.OpenLoopVoltage; 279 /** 280 * The type of control request to use for the drive motor. 281 */ 282 public SwerveModule.SteerRequestType SteerRequestType = SwerveModule.SteerRequestType.Position; 283 /** 284 * Whether to desaturate wheel speeds before applying. For more information, see 285 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 286 */ 287 public boolean DesaturateWheelSpeeds = true; 288 /** 289 * The perspective to use when determining which direction is forward. 290 */ 291 public ForwardPerspectiveValue ForwardPerspective = ForwardPerspectiveValue.OperatorPerspective; 292 293 /** 294 * Modifies the VelocityX parameter and returns itself. 295 * <p> 296 * The velocity in the X direction, in m/s. X is defined as forward according to 297 * WPILib convention, so this determines how fast to travel forward. 298 * 299 * @param newVelocityX Parameter to modify 300 * @return this object 301 */ 302 public FieldCentric withVelocityX(double newVelocityX) { 303 this.VelocityX = newVelocityX; 304 return this; 305 } 306 307 /** 308 * Modifies the VelocityX parameter and returns itself. 309 * <p> 310 * The velocity in the X direction, in m/s. X is defined as forward according to 311 * WPILib convention, so this determines how fast to travel forward. 312 * 313 * @param newVelocityX Parameter to modify 314 * @return this object 315 */ 316 public FieldCentric withVelocityX(LinearVelocity newVelocityX) { 317 this.VelocityX = newVelocityX.in(MetersPerSecond); 318 return this; 319 } 320 321 /** 322 * Modifies the VelocityY parameter and returns itself. 323 * <p> 324 * The velocity in the Y direction, in m/s. Y is defined as to the left 325 * according to WPILib convention, so this determines how fast to travel to the 326 * left. 327 * 328 * @param newVelocityY Parameter to modify 329 * @return this object 330 */ 331 public FieldCentric withVelocityY(double newVelocityY) { 332 this.VelocityY = newVelocityY; 333 return this; 334 } 335 336 /** 337 * Modifies the VelocityY parameter and returns itself. 338 * <p> 339 * The velocity in the Y direction, in m/s. Y is defined as to the left 340 * according to WPILib convention, so this determines how fast to travel to the 341 * left. 342 * 343 * @param newVelocityY Parameter to modify 344 * @return this object 345 */ 346 public FieldCentric withVelocityY(LinearVelocity newVelocityY) { 347 this.VelocityY = newVelocityY.in(MetersPerSecond); 348 return this; 349 } 350 351 /** 352 * Modifies the RotationalRate parameter and returns itself. 353 * <p> 354 * The angular rate to rotate at, in radians per second. Angular rate is defined 355 * as counterclockwise positive, so this determines how fast to turn 356 * counterclockwise. 357 * 358 * @param newRotationalRate Parameter to modify 359 * @return this object 360 */ 361 public FieldCentric withRotationalRate(double newRotationalRate) { 362 this.RotationalRate = newRotationalRate; 363 return this; 364 } 365 366 /** 367 * Modifies the RotationalRate parameter and returns itself. 368 * <p> 369 * The angular rate to rotate at, in radians per second. Angular rate is defined 370 * as counterclockwise positive, so this determines how fast to turn 371 * counterclockwise. 372 * 373 * @param newRotationalRate Parameter to modify 374 * @return this object 375 */ 376 public FieldCentric withRotationalRate(AngularVelocity newRotationalRate) { 377 this.RotationalRate = newRotationalRate.in(RadiansPerSecond); 378 return this; 379 } 380 381 /** 382 * Modifies the Deadband parameter and returns itself. 383 * <p> 384 * The allowable deadband of the request, in m/s. 385 * 386 * @param newDeadband Parameter to modify 387 * @return this object 388 */ 389 public FieldCentric withDeadband(double newDeadband) { 390 this.Deadband = newDeadband; 391 return this; 392 } 393 394 /** 395 * Modifies the Deadband parameter and returns itself. 396 * <p> 397 * The allowable deadband of the request, in m/s. 398 * 399 * @param newDeadband Parameter to modify 400 * @return this object 401 */ 402 public FieldCentric withDeadband(LinearVelocity newDeadband) { 403 this.Deadband = newDeadband.in(MetersPerSecond); 404 return this; 405 } 406 407 /** 408 * Modifies the RotationalDeadband parameter and returns itself. 409 * <p> 410 * The rotational deadband of the request, in radians per second. 411 * 412 * @param newRotationalDeadband Parameter to modify 413 * @return this object 414 */ 415 public FieldCentric withRotationalDeadband(double newRotationalDeadband) { 416 this.RotationalDeadband = newRotationalDeadband; 417 return this; 418 } 419 420 /** 421 * Modifies the RotationalDeadband parameter and returns itself. 422 * <p> 423 * The rotational deadband of the request, in radians per second. 424 * 425 * @param newRotationalDeadband Parameter to modify 426 * @return this object 427 */ 428 public FieldCentric withRotationalDeadband(AngularVelocity newRotationalDeadband) { 429 this.RotationalDeadband = newRotationalDeadband.in(RadiansPerSecond); 430 return this; 431 } 432 433 /** 434 * Modifies the CenterOfRotation parameter and returns itself. 435 * <p> 436 * The center of rotation the robot should rotate around. This is (0,0) by 437 * default, which will rotate around the center of the robot. 438 * 439 * @param newCenterOfRotation Parameter to modify 440 * @return this object 441 */ 442 public FieldCentric withCenterOfRotation(Translation2d newCenterOfRotation) { 443 this.CenterOfRotation = newCenterOfRotation; 444 return this; 445 } 446 447 /** 448 * Modifies the DriveRequestType parameter and returns itself. 449 * <p> 450 * The type of control request to use for the drive motor. 451 * 452 * @param newDriveRequestType Parameter to modify 453 * @return this object 454 */ 455 public FieldCentric withDriveRequestType(SwerveModule.DriveRequestType newDriveRequestType) { 456 this.DriveRequestType = newDriveRequestType; 457 return this; 458 } 459 460 /** 461 * Modifies the SteerRequestType parameter and returns itself. 462 * <p> 463 * The type of control request to use for the drive motor. 464 * 465 * @param newSteerRequestType Parameter to modify 466 * @return this object 467 */ 468 public FieldCentric withSteerRequestType(SwerveModule.SteerRequestType newSteerRequestType) { 469 this.SteerRequestType = newSteerRequestType; 470 return this; 471 } 472 473 /** 474 * Modifies the DesaturateWheelSpeeds parameter and returns itself. 475 * <p> 476 * Whether to desaturate wheel speeds before applying. For more information, see 477 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 478 * 479 * @param newDesaturateWheelSpeeds Parameter to modify 480 * @return this object 481 */ 482 public FieldCentric withDesaturateWheelSpeeds(boolean newDesaturateWheelSpeeds) { 483 this.DesaturateWheelSpeeds = newDesaturateWheelSpeeds; 484 return this; 485 } 486 487 /** 488 * Modifies the ForwardPerspective parameter and returns itself. 489 * <p> 490 * The perspective to use when determining which direction is forward. 491 * 492 * @param newForwardPerspective Parameter to modify 493 * @return this object 494 */ 495 public FieldCentric withForwardPerspective(ForwardPerspectiveValue newForwardPerspective) { 496 this.ForwardPerspective = newForwardPerspective; 497 return this; 498 } 499 500 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 501 return StatusCode.valueOf(SwerveJNI.JNI_Request_Apply_FieldCentric(parameters.drivetrainId, 502 VelocityX, 503 VelocityY, 504 RotationalRate, 505 Deadband, 506 RotationalDeadband, 507 CenterOfRotation.getX(), 508 CenterOfRotation.getY(), 509 DriveRequestType.value, 510 SteerRequestType.value, 511 DesaturateWheelSpeeds, 512 ForwardPerspective.value)); 513 } 514 515 public void applyNative(int id) { 516 SwerveJNI.JNI_SetControl_FieldCentric(id, 517 VelocityX, 518 VelocityY, 519 RotationalRate, 520 Deadband, 521 RotationalDeadband, 522 CenterOfRotation.getX(), 523 CenterOfRotation.getY(), 524 DriveRequestType.value, 525 SteerRequestType.value, 526 DesaturateWheelSpeeds, 527 ForwardPerspective.value); 528 } 529 } 530 531 /** 532 * Drives the swerve drivetrain in a robot-centric manner. This request is 533 * optimized for joystick control during teleop with built-in deadbands. 534 * <p> 535 * This request specifies the direction the robot should travel oriented against 536 * the robot itself, and the rate at which their robot should rotate about the 537 * center of the robot. 538 * <p> 539 * An example scenario is that the robot is oriented to the field +Y (left), the 540 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. In 541 * this scenario, the robot would drive forward relative to itself (or left 542 * along the field +Y) at 5 m/s and turn counterclockwise at 0.5 rad/s. 543 */ 544 public static class RobotCentric implements NativeSwerveRequest { 545 /** 546 * The velocity in the X direction, in m/s. X is defined as forward according to 547 * WPILib convention, so this determines how fast to travel forward. 548 */ 549 public double VelocityX = 0; 550 /** 551 * The velocity in the Y direction, in m/s. Y is defined as to the left 552 * according to WPILib convention, so this determines how fast to travel to the 553 * left. 554 */ 555 public double VelocityY = 0; 556 /** 557 * The angular rate to rotate at, in radians per second. Angular rate is defined 558 * as counterclockwise positive, so this determines how fast to turn 559 * counterclockwise. 560 */ 561 public double RotationalRate = 0; 562 /** 563 * The allowable deadband of the request, in m/s. 564 */ 565 public double Deadband = 0; 566 /** 567 * The rotational deadband of the request, in radians per second. 568 */ 569 public double RotationalDeadband = 0; 570 /** 571 * The center of rotation the robot should rotate around. This is (0,0) by 572 * default, which will rotate around the center of the robot. 573 */ 574 public Translation2d CenterOfRotation = new Translation2d(); 575 /** 576 * The type of control request to use for the drive motor. 577 */ 578 public SwerveModule.DriveRequestType DriveRequestType = SwerveModule.DriveRequestType.OpenLoopVoltage; 579 /** 580 * The type of control request to use for the drive motor. 581 */ 582 public SwerveModule.SteerRequestType SteerRequestType = SwerveModule.SteerRequestType.Position; 583 /** 584 * Whether to desaturate wheel speeds before applying. For more information, see 585 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 586 */ 587 public boolean DesaturateWheelSpeeds = true; 588 589 /** 590 * Modifies the VelocityX parameter and returns itself. 591 * <p> 592 * The velocity in the X direction, in m/s. X is defined as forward according to 593 * WPILib convention, so this determines how fast to travel forward. 594 * 595 * @param newVelocityX Parameter to modify 596 * @return this object 597 */ 598 public RobotCentric withVelocityX(double newVelocityX) { 599 this.VelocityX = newVelocityX; 600 return this; 601 } 602 603 /** 604 * Modifies the VelocityX parameter and returns itself. 605 * <p> 606 * The velocity in the X direction, in m/s. X is defined as forward according to 607 * WPILib convention, so this determines how fast to travel forward. 608 * 609 * @param newVelocityX Parameter to modify 610 * @return this object 611 */ 612 public RobotCentric withVelocityX(LinearVelocity newVelocityX) { 613 this.VelocityX = newVelocityX.in(MetersPerSecond); 614 return this; 615 } 616 617 /** 618 * Modifies the VelocityY parameter and returns itself. 619 * <p> 620 * The velocity in the Y direction, in m/s. Y is defined as to the left 621 * according to WPILib convention, so this determines how fast to travel to the 622 * left. 623 * 624 * @param newVelocityY Parameter to modify 625 * @return this object 626 */ 627 public RobotCentric withVelocityY(double newVelocityY) { 628 this.VelocityY = newVelocityY; 629 return this; 630 } 631 632 /** 633 * Modifies the VelocityY parameter and returns itself. 634 * <p> 635 * The velocity in the Y direction, in m/s. Y is defined as to the left 636 * according to WPILib convention, so this determines how fast to travel to the 637 * left. 638 * 639 * @param newVelocityY Parameter to modify 640 * @return this object 641 */ 642 public RobotCentric withVelocityY(LinearVelocity newVelocityY) { 643 this.VelocityY = newVelocityY.in(MetersPerSecond); 644 return this; 645 } 646 647 /** 648 * Modifies the RotationalRate parameter and returns itself. 649 * <p> 650 * The angular rate to rotate at, in radians per second. Angular rate is defined 651 * as counterclockwise positive, so this determines how fast to turn 652 * counterclockwise. 653 * 654 * @param newRotationalRate Parameter to modify 655 * @return this object 656 */ 657 public RobotCentric withRotationalRate(double newRotationalRate) { 658 this.RotationalRate = newRotationalRate; 659 return this; 660 } 661 662 /** 663 * Modifies the RotationalRate parameter and returns itself. 664 * <p> 665 * The angular rate to rotate at, in radians per second. Angular rate is defined 666 * as counterclockwise positive, so this determines how fast to turn 667 * counterclockwise. 668 * 669 * @param newRotationalRate Parameter to modify 670 * @return this object 671 */ 672 public RobotCentric withRotationalRate(AngularVelocity newRotationalRate) { 673 this.RotationalRate = newRotationalRate.in(RadiansPerSecond); 674 return this; 675 } 676 677 /** 678 * Modifies the Deadband parameter and returns itself. 679 * <p> 680 * The allowable deadband of the request, in m/s. 681 * 682 * @param newDeadband Parameter to modify 683 * @return this object 684 */ 685 public RobotCentric withDeadband(double newDeadband) { 686 this.Deadband = newDeadband; 687 return this; 688 } 689 690 /** 691 * Modifies the Deadband parameter and returns itself. 692 * <p> 693 * The allowable deadband of the request, in m/s. 694 * 695 * @param newDeadband Parameter to modify 696 * @return this object 697 */ 698 public RobotCentric withDeadband(LinearVelocity newDeadband) { 699 this.Deadband = newDeadband.in(MetersPerSecond); 700 return this; 701 } 702 703 /** 704 * Modifies the RotationalDeadband parameter and returns itself. 705 * <p> 706 * The rotational deadband of the request, in radians per second. 707 * 708 * @param newRotationalDeadband Parameter to modify 709 * @return this object 710 */ 711 public RobotCentric withRotationalDeadband(double newRotationalDeadband) { 712 this.RotationalDeadband = newRotationalDeadband; 713 return this; 714 } 715 716 /** 717 * Modifies the RotationalDeadband parameter and returns itself. 718 * <p> 719 * The rotational deadband of the request, in radians per second. 720 * 721 * @param newRotationalDeadband Parameter to modify 722 * @return this object 723 */ 724 public RobotCentric withRotationalDeadband(AngularVelocity newRotationalDeadband) { 725 this.RotationalDeadband = newRotationalDeadband.in(RadiansPerSecond); 726 return this; 727 } 728 729 /** 730 * Modifies the CenterOfRotation parameter and returns itself. 731 * <p> 732 * The center of rotation the robot should rotate around. This is (0,0) by 733 * default, which will rotate around the center of the robot. 734 * 735 * @param newCenterOfRotation Parameter to modify 736 * @return this object 737 */ 738 public RobotCentric withCenterOfRotation(Translation2d newCenterOfRotation) { 739 this.CenterOfRotation = newCenterOfRotation; 740 return this; 741 } 742 743 /** 744 * Modifies the DriveRequestType parameter and returns itself. 745 * <p> 746 * The type of control request to use for the drive motor. 747 * 748 * @param newDriveRequestType Parameter to modify 749 * @return this object 750 */ 751 public RobotCentric withDriveRequestType(SwerveModule.DriveRequestType newDriveRequestType) { 752 this.DriveRequestType = newDriveRequestType; 753 return this; 754 } 755 756 /** 757 * Modifies the SteerRequestType parameter and returns itself. 758 * <p> 759 * The type of control request to use for the drive motor. 760 * 761 * @param newSteerRequestType Parameter to modify 762 * @return this object 763 */ 764 public RobotCentric withSteerRequestType(SwerveModule.SteerRequestType newSteerRequestType) { 765 this.SteerRequestType = newSteerRequestType; 766 return this; 767 } 768 769 /** 770 * Modifies the DesaturateWheelSpeeds parameter and returns itself. 771 * <p> 772 * Whether to desaturate wheel speeds before applying. For more information, see 773 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 774 * 775 * @param newDesaturateWheelSpeeds Parameter to modify 776 * @return this object 777 */ 778 public RobotCentric withDesaturateWheelSpeeds(boolean newDesaturateWheelSpeeds) { 779 this.DesaturateWheelSpeeds = newDesaturateWheelSpeeds; 780 return this; 781 } 782 783 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 784 return StatusCode.valueOf(SwerveJNI.JNI_Request_Apply_RobotCentric(parameters.drivetrainId, 785 VelocityX, 786 VelocityY, 787 RotationalRate, 788 Deadband, 789 RotationalDeadband, 790 CenterOfRotation.getX(), 791 CenterOfRotation.getY(), 792 DriveRequestType.value, 793 SteerRequestType.value, 794 DesaturateWheelSpeeds)); 795 } 796 797 public void applyNative(int id) { 798 SwerveJNI.JNI_SetControl_RobotCentric(id, 799 VelocityX, 800 VelocityY, 801 RotationalRate, 802 Deadband, 803 RotationalDeadband, 804 CenterOfRotation.getX(), 805 CenterOfRotation.getY(), 806 DriveRequestType.value, 807 SteerRequestType.value, 808 DesaturateWheelSpeeds); 809 } 810 } 811 812 /** 813 * Sets the swerve drive modules to point to a specified direction. 814 */ 815 public static class PointWheelsAt implements NativeSwerveRequest { 816 /** 817 * The direction to point the modules toward. This direction is still optimized 818 * to what the module was previously at. 819 */ 820 public Rotation2d ModuleDirection = new Rotation2d(); 821 /** 822 * The type of control request to use for the drive motor. 823 */ 824 public SwerveModule.DriveRequestType DriveRequestType = SwerveModule.DriveRequestType.OpenLoopVoltage; 825 /** 826 * The type of control request to use for the drive motor. 827 */ 828 public SwerveModule.SteerRequestType SteerRequestType = SwerveModule.SteerRequestType.Position; 829 830 /** 831 * Modifies the ModuleDirection parameter and returns itself. 832 * <p> 833 * The direction to point the modules toward. This direction is still optimized 834 * to what the module was previously at. 835 * 836 * @param newModuleDirection Parameter to modify 837 * @return this object 838 */ 839 public PointWheelsAt withModuleDirection(Rotation2d newModuleDirection) { 840 this.ModuleDirection = newModuleDirection; 841 return this; 842 } 843 844 /** 845 * Modifies the DriveRequestType parameter and returns itself. 846 * <p> 847 * The type of control request to use for the drive motor. 848 * 849 * @param newDriveRequestType Parameter to modify 850 * @return this object 851 */ 852 public PointWheelsAt withDriveRequestType(SwerveModule.DriveRequestType newDriveRequestType) { 853 this.DriveRequestType = newDriveRequestType; 854 return this; 855 } 856 857 /** 858 * Modifies the SteerRequestType parameter and returns itself. 859 * <p> 860 * The type of control request to use for the drive motor. 861 * 862 * @param newSteerRequestType Parameter to modify 863 * @return this object 864 */ 865 public PointWheelsAt withSteerRequestType(SwerveModule.SteerRequestType newSteerRequestType) { 866 this.SteerRequestType = newSteerRequestType; 867 return this; 868 } 869 870 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 871 return StatusCode.valueOf(SwerveJNI.JNI_Request_Apply_PointWheelsAt(parameters.drivetrainId, 872 ModuleDirection.getRadians(), 873 DriveRequestType.value, 874 SteerRequestType.value)); 875 } 876 877 public void applyNative(int id) { 878 SwerveJNI.JNI_SetControl_PointWheelsAt(id, 879 ModuleDirection.getRadians(), 880 DriveRequestType.value, 881 SteerRequestType.value); 882 } 883 } 884 885 /** 886 * Accepts a generic robot-centric ChassisSpeeds to apply to the drivetrain. 887 * This request is optimized for autonomous or profiled control, which typically 888 * directly provides ChassisSpeeds and optionally wheel force feedforwards. 889 * <p> 890 * Unlike the field-centric requests, this request does not automatically 891 * discretize the provided ChassisSpeeds. 892 */ 893 public static class ApplyRobotSpeeds implements NativeSwerveRequest { 894 /** 895 * The robot-centric chassis speeds to apply to the drivetrain. 896 * Users must manually discretize these speeds if appropriate. 897 */ 898 public ChassisSpeeds Speeds = new ChassisSpeeds(); 899 /** 900 * Robot-centric wheel force feedforwards to apply in the X direction, in 901 * newtons. X is defined as forward according to WPILib convention, so this 902 * determines the forward forces to apply. 903 * <p> 904 * These forces should include friction applied to the ground. 905 * <p> 906 * The order of the forces should match the order of the modules returned from 907 * SwerveDrivetrain. 908 */ 909 public double[] WheelForceFeedforwardsX = {}; 910 /** 911 * Robot-centric wheel force feedforwards to apply in the Y direction, in 912 * newtons. Y is defined as to the left according to WPILib convention, so this 913 * determines the forces to apply to the left. 914 * <p> 915 * These forces should include friction applied to the ground. 916 * <p> 917 * The order of the forces should match the order of the modules returned from 918 * SwerveDrivetrain. 919 */ 920 public double[] WheelForceFeedforwardsY = {}; 921 /** 922 * The center of rotation the robot should rotate around. This is (0,0) by 923 * default, which will rotate around the center of the robot. 924 */ 925 public Translation2d CenterOfRotation = new Translation2d(); 926 /** 927 * The type of control request to use for the drive motor. 928 */ 929 public SwerveModule.DriveRequestType DriveRequestType = SwerveModule.DriveRequestType.OpenLoopVoltage; 930 /** 931 * The type of control request to use for the drive motor. 932 */ 933 public SwerveModule.SteerRequestType SteerRequestType = SwerveModule.SteerRequestType.Position; 934 /** 935 * Whether to desaturate wheel speeds before applying. For more information, see 936 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 937 */ 938 public boolean DesaturateWheelSpeeds = true; 939 940 /** 941 * Modifies the Speeds parameter and returns itself. 942 * <p> 943 * The robot-centric chassis speeds to apply to the drivetrain. 944 * Users must manually discretize these speeds if appropriate. 945 * 946 * @param newSpeeds Parameter to modify 947 * @return this object 948 */ 949 public ApplyRobotSpeeds withSpeeds(ChassisSpeeds newSpeeds) { 950 this.Speeds = newSpeeds; 951 return this; 952 } 953 954 /** 955 * Modifies the WheelForceFeedforwardsX parameter and returns itself. 956 * <p> 957 * Robot-centric wheel force feedforwards to apply in the X direction, in 958 * newtons. X is defined as forward according to WPILib convention, so this 959 * determines the forward forces to apply. 960 * <p> 961 * These forces should include friction applied to the ground. 962 * <p> 963 * The order of the forces should match the order of the modules returned from 964 * SwerveDrivetrain. 965 * 966 * @param newWheelForceFeedforwardsX Parameter to modify 967 * @return this object 968 */ 969 public ApplyRobotSpeeds withWheelForceFeedforwardsX(double[] newWheelForceFeedforwardsX) { 970 this.WheelForceFeedforwardsX = newWheelForceFeedforwardsX; 971 return this; 972 } 973 974 /** 975 * Modifies the WheelForceFeedforwardsX parameter and returns itself. 976 * <p> 977 * Robot-centric wheel force feedforwards to apply in the X direction, in 978 * newtons. X is defined as forward according to WPILib convention, so this 979 * determines the forward forces to apply. 980 * <p> 981 * These forces should include friction applied to the ground. 982 * <p> 983 * The order of the forces should match the order of the modules returned from 984 * SwerveDrivetrain. 985 * 986 * @param newWheelForceFeedforwardsX Parameter to modify 987 * @return this object 988 */ 989 public ApplyRobotSpeeds withWheelForceFeedforwardsX(Force[] newWheelForceFeedforwardsX) { 990 if (this.WheelForceFeedforwardsX.length != newWheelForceFeedforwardsX.length) { 991 this.WheelForceFeedforwardsX = new double[newWheelForceFeedforwardsX.length]; 992 } 993 for (int i = 0; i < this.WheelForceFeedforwardsX.length; ++i) { 994 this.WheelForceFeedforwardsX[i] = newWheelForceFeedforwardsX[i].in(Newtons); 995 } 996 997 return this; 998 } 999 1000 /** 1001 * Modifies the WheelForceFeedforwardsY parameter and returns itself. 1002 * <p> 1003 * Robot-centric wheel force feedforwards to apply in the Y direction, in 1004 * newtons. Y is defined as to the left according to WPILib convention, so this 1005 * determines the forces to apply to the left. 1006 * <p> 1007 * These forces should include friction applied to the ground. 1008 * <p> 1009 * The order of the forces should match the order of the modules returned from 1010 * SwerveDrivetrain. 1011 * 1012 * @param newWheelForceFeedforwardsY Parameter to modify 1013 * @return this object 1014 */ 1015 public ApplyRobotSpeeds withWheelForceFeedforwardsY(double[] newWheelForceFeedforwardsY) { 1016 this.WheelForceFeedforwardsY = newWheelForceFeedforwardsY; 1017 return this; 1018 } 1019 1020 /** 1021 * Modifies the WheelForceFeedforwardsY parameter and returns itself. 1022 * <p> 1023 * Robot-centric wheel force feedforwards to apply in the Y direction, in 1024 * newtons. Y is defined as to the left according to WPILib convention, so this 1025 * determines the forces to apply to the left. 1026 * <p> 1027 * These forces should include friction applied to the ground. 1028 * <p> 1029 * The order of the forces should match the order of the modules returned from 1030 * SwerveDrivetrain. 1031 * 1032 * @param newWheelForceFeedforwardsY Parameter to modify 1033 * @return this object 1034 */ 1035 public ApplyRobotSpeeds withWheelForceFeedforwardsY(Force[] newWheelForceFeedforwardsY) { 1036 if (this.WheelForceFeedforwardsY.length != newWheelForceFeedforwardsY.length) { 1037 this.WheelForceFeedforwardsY = new double[newWheelForceFeedforwardsY.length]; 1038 } 1039 for (int i = 0; i < this.WheelForceFeedforwardsY.length; ++i) { 1040 this.WheelForceFeedforwardsY[i] = newWheelForceFeedforwardsY[i].in(Newtons); 1041 } 1042 1043 return this; 1044 } 1045 1046 /** 1047 * Modifies the CenterOfRotation parameter and returns itself. 1048 * <p> 1049 * The center of rotation the robot should rotate around. This is (0,0) by 1050 * default, which will rotate around the center of the robot. 1051 * 1052 * @param newCenterOfRotation Parameter to modify 1053 * @return this object 1054 */ 1055 public ApplyRobotSpeeds withCenterOfRotation(Translation2d newCenterOfRotation) { 1056 this.CenterOfRotation = newCenterOfRotation; 1057 return this; 1058 } 1059 1060 /** 1061 * Modifies the DriveRequestType parameter and returns itself. 1062 * <p> 1063 * The type of control request to use for the drive motor. 1064 * 1065 * @param newDriveRequestType Parameter to modify 1066 * @return this object 1067 */ 1068 public ApplyRobotSpeeds withDriveRequestType(SwerveModule.DriveRequestType newDriveRequestType) { 1069 this.DriveRequestType = newDriveRequestType; 1070 return this; 1071 } 1072 1073 /** 1074 * Modifies the SteerRequestType parameter and returns itself. 1075 * <p> 1076 * The type of control request to use for the drive motor. 1077 * 1078 * @param newSteerRequestType Parameter to modify 1079 * @return this object 1080 */ 1081 public ApplyRobotSpeeds withSteerRequestType(SwerveModule.SteerRequestType newSteerRequestType) { 1082 this.SteerRequestType = newSteerRequestType; 1083 return this; 1084 } 1085 1086 /** 1087 * Modifies the DesaturateWheelSpeeds parameter and returns itself. 1088 * <p> 1089 * Whether to desaturate wheel speeds before applying. For more information, see 1090 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 1091 * 1092 * @param newDesaturateWheelSpeeds Parameter to modify 1093 * @return this object 1094 */ 1095 public ApplyRobotSpeeds withDesaturateWheelSpeeds(boolean newDesaturateWheelSpeeds) { 1096 this.DesaturateWheelSpeeds = newDesaturateWheelSpeeds; 1097 return this; 1098 } 1099 1100 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 1101 return StatusCode.valueOf(SwerveJNI.JNI_Request_Apply_ApplyRobotSpeeds(parameters.drivetrainId, 1102 Speeds.vxMetersPerSecond, 1103 Speeds.vyMetersPerSecond, 1104 Speeds.omegaRadiansPerSecond, 1105 WheelForceFeedforwardsX, 1106 WheelForceFeedforwardsY, 1107 CenterOfRotation.getX(), 1108 CenterOfRotation.getY(), 1109 DriveRequestType.value, 1110 SteerRequestType.value, 1111 DesaturateWheelSpeeds)); 1112 } 1113 1114 public void applyNative(int id) { 1115 SwerveJNI.JNI_SetControl_ApplyRobotSpeeds(id, 1116 Speeds.vxMetersPerSecond, 1117 Speeds.vyMetersPerSecond, 1118 Speeds.omegaRadiansPerSecond, 1119 WheelForceFeedforwardsX, 1120 WheelForceFeedforwardsY, 1121 CenterOfRotation.getX(), 1122 CenterOfRotation.getY(), 1123 DriveRequestType.value, 1124 SteerRequestType.value, 1125 DesaturateWheelSpeeds); 1126 } 1127 } 1128 1129 /** 1130 * Accepts a generic field-centric ChassisSpeeds to apply to the drivetrain. 1131 * This request is optimized for autonomous or profiled control, which typically 1132 * directly provides ChassisSpeeds and optionally wheel force feedforwards. 1133 */ 1134 public static class ApplyFieldSpeeds implements NativeSwerveRequest { 1135 /** 1136 * The field-centric chassis speeds to apply to the drivetrain. 1137 */ 1138 public ChassisSpeeds Speeds = new ChassisSpeeds(); 1139 /** 1140 * Field-centric wheel force feedforwards to apply in the X direction, in 1141 * newtons. X is defined as forward according to WPILib convention, so this 1142 * determines the forward forces to apply. 1143 * <p> 1144 * These forces should include friction applied to the ground. 1145 * <p> 1146 * The order of the forces should match the order of the modules returned from 1147 * SwerveDrivetrain. 1148 */ 1149 public double[] WheelForceFeedforwardsX = {}; 1150 /** 1151 * Field-centric wheel force feedforwards to apply in the Y direction, in 1152 * newtons. Y is defined as to the left according to WPILib convention, so this 1153 * determines the forces to apply to the left. 1154 * <p> 1155 * These forces should include friction applied to the ground. 1156 * <p> 1157 * The order of the forces should match the order of the modules returned from 1158 * SwerveDrivetrain. 1159 */ 1160 public double[] WheelForceFeedforwardsY = {}; 1161 /** 1162 * The center of rotation the robot should rotate around. This is (0,0) by 1163 * default, which will rotate around the center of the robot. 1164 */ 1165 public Translation2d CenterOfRotation = new Translation2d(); 1166 /** 1167 * The type of control request to use for the drive motor. 1168 */ 1169 public SwerveModule.DriveRequestType DriveRequestType = SwerveModule.DriveRequestType.OpenLoopVoltage; 1170 /** 1171 * The type of control request to use for the drive motor. 1172 */ 1173 public SwerveModule.SteerRequestType SteerRequestType = SwerveModule.SteerRequestType.Position; 1174 /** 1175 * Whether to desaturate wheel speeds before applying. For more information, see 1176 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 1177 */ 1178 public boolean DesaturateWheelSpeeds = true; 1179 /** 1180 * The perspective to use when determining which direction is forward. 1181 */ 1182 public ForwardPerspectiveValue ForwardPerspective = ForwardPerspectiveValue.BlueAlliance; 1183 1184 /** 1185 * Modifies the Speeds parameter and returns itself. 1186 * <p> 1187 * The field-centric chassis speeds to apply to the drivetrain. 1188 * 1189 * @param newSpeeds Parameter to modify 1190 * @return this object 1191 */ 1192 public ApplyFieldSpeeds withSpeeds(ChassisSpeeds newSpeeds) { 1193 this.Speeds = newSpeeds; 1194 return this; 1195 } 1196 1197 /** 1198 * Modifies the WheelForceFeedforwardsX parameter and returns itself. 1199 * <p> 1200 * Field-centric wheel force feedforwards to apply in the X direction, in 1201 * newtons. X is defined as forward according to WPILib convention, so this 1202 * determines the forward forces to apply. 1203 * <p> 1204 * These forces should include friction applied to the ground. 1205 * <p> 1206 * The order of the forces should match the order of the modules returned from 1207 * SwerveDrivetrain. 1208 * 1209 * @param newWheelForceFeedforwardsX Parameter to modify 1210 * @return this object 1211 */ 1212 public ApplyFieldSpeeds withWheelForceFeedforwardsX(double[] newWheelForceFeedforwardsX) { 1213 this.WheelForceFeedforwardsX = newWheelForceFeedforwardsX; 1214 return this; 1215 } 1216 1217 /** 1218 * Modifies the WheelForceFeedforwardsX parameter and returns itself. 1219 * <p> 1220 * Field-centric wheel force feedforwards to apply in the X direction, in 1221 * newtons. X is defined as forward according to WPILib convention, so this 1222 * determines the forward forces to apply. 1223 * <p> 1224 * These forces should include friction applied to the ground. 1225 * <p> 1226 * The order of the forces should match the order of the modules returned from 1227 * SwerveDrivetrain. 1228 * 1229 * @param newWheelForceFeedforwardsX Parameter to modify 1230 * @return this object 1231 */ 1232 public ApplyFieldSpeeds withWheelForceFeedforwardsX(Force[] newWheelForceFeedforwardsX) { 1233 if (this.WheelForceFeedforwardsX.length != newWheelForceFeedforwardsX.length) { 1234 this.WheelForceFeedforwardsX = new double[newWheelForceFeedforwardsX.length]; 1235 } 1236 for (int i = 0; i < this.WheelForceFeedforwardsX.length; ++i) { 1237 this.WheelForceFeedforwardsX[i] = newWheelForceFeedforwardsX[i].in(Newtons); 1238 } 1239 1240 return this; 1241 } 1242 1243 /** 1244 * Modifies the WheelForceFeedforwardsY parameter and returns itself. 1245 * <p> 1246 * Field-centric wheel force feedforwards to apply in the Y direction, in 1247 * newtons. Y is defined as to the left according to WPILib convention, so this 1248 * determines the forces to apply to the left. 1249 * <p> 1250 * These forces should include friction applied to the ground. 1251 * <p> 1252 * The order of the forces should match the order of the modules returned from 1253 * SwerveDrivetrain. 1254 * 1255 * @param newWheelForceFeedforwardsY Parameter to modify 1256 * @return this object 1257 */ 1258 public ApplyFieldSpeeds withWheelForceFeedforwardsY(double[] newWheelForceFeedforwardsY) { 1259 this.WheelForceFeedforwardsY = newWheelForceFeedforwardsY; 1260 return this; 1261 } 1262 1263 /** 1264 * Modifies the WheelForceFeedforwardsY parameter and returns itself. 1265 * <p> 1266 * Field-centric wheel force feedforwards to apply in the Y direction, in 1267 * newtons. Y is defined as to the left according to WPILib convention, so this 1268 * determines the forces to apply to the left. 1269 * <p> 1270 * These forces should include friction applied to the ground. 1271 * <p> 1272 * The order of the forces should match the order of the modules returned from 1273 * SwerveDrivetrain. 1274 * 1275 * @param newWheelForceFeedforwardsY Parameter to modify 1276 * @return this object 1277 */ 1278 public ApplyFieldSpeeds withWheelForceFeedforwardsY(Force[] newWheelForceFeedforwardsY) { 1279 if (this.WheelForceFeedforwardsY.length != newWheelForceFeedforwardsY.length) { 1280 this.WheelForceFeedforwardsY = new double[newWheelForceFeedforwardsY.length]; 1281 } 1282 for (int i = 0; i < this.WheelForceFeedforwardsY.length; ++i) { 1283 this.WheelForceFeedforwardsY[i] = newWheelForceFeedforwardsY[i].in(Newtons); 1284 } 1285 1286 return this; 1287 } 1288 1289 /** 1290 * Modifies the CenterOfRotation parameter and returns itself. 1291 * <p> 1292 * The center of rotation the robot should rotate around. This is (0,0) by 1293 * default, which will rotate around the center of the robot. 1294 * 1295 * @param newCenterOfRotation Parameter to modify 1296 * @return this object 1297 */ 1298 public ApplyFieldSpeeds withCenterOfRotation(Translation2d newCenterOfRotation) { 1299 this.CenterOfRotation = newCenterOfRotation; 1300 return this; 1301 } 1302 1303 /** 1304 * Modifies the DriveRequestType parameter and returns itself. 1305 * <p> 1306 * The type of control request to use for the drive motor. 1307 * 1308 * @param newDriveRequestType Parameter to modify 1309 * @return this object 1310 */ 1311 public ApplyFieldSpeeds withDriveRequestType(SwerveModule.DriveRequestType newDriveRequestType) { 1312 this.DriveRequestType = newDriveRequestType; 1313 return this; 1314 } 1315 1316 /** 1317 * Modifies the SteerRequestType parameter and returns itself. 1318 * <p> 1319 * The type of control request to use for the drive motor. 1320 * 1321 * @param newSteerRequestType Parameter to modify 1322 * @return this object 1323 */ 1324 public ApplyFieldSpeeds withSteerRequestType(SwerveModule.SteerRequestType newSteerRequestType) { 1325 this.SteerRequestType = newSteerRequestType; 1326 return this; 1327 } 1328 1329 /** 1330 * Modifies the DesaturateWheelSpeeds parameter and returns itself. 1331 * <p> 1332 * Whether to desaturate wheel speeds before applying. For more information, see 1333 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 1334 * 1335 * @param newDesaturateWheelSpeeds Parameter to modify 1336 * @return this object 1337 */ 1338 public ApplyFieldSpeeds withDesaturateWheelSpeeds(boolean newDesaturateWheelSpeeds) { 1339 this.DesaturateWheelSpeeds = newDesaturateWheelSpeeds; 1340 return this; 1341 } 1342 1343 /** 1344 * Modifies the ForwardPerspective parameter and returns itself. 1345 * <p> 1346 * The perspective to use when determining which direction is forward. 1347 * 1348 * @param newForwardPerspective Parameter to modify 1349 * @return this object 1350 */ 1351 public ApplyFieldSpeeds withForwardPerspective(ForwardPerspectiveValue newForwardPerspective) { 1352 this.ForwardPerspective = newForwardPerspective; 1353 return this; 1354 } 1355 1356 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 1357 return StatusCode.valueOf(SwerveJNI.JNI_Request_Apply_ApplyFieldSpeeds(parameters.drivetrainId, 1358 Speeds.vxMetersPerSecond, 1359 Speeds.vyMetersPerSecond, 1360 Speeds.omegaRadiansPerSecond, 1361 WheelForceFeedforwardsX, 1362 WheelForceFeedforwardsY, 1363 CenterOfRotation.getX(), 1364 CenterOfRotation.getY(), 1365 DriveRequestType.value, 1366 SteerRequestType.value, 1367 DesaturateWheelSpeeds, 1368 ForwardPerspective.value)); 1369 } 1370 1371 public void applyNative(int id) { 1372 SwerveJNI.JNI_SetControl_ApplyFieldSpeeds(id, 1373 Speeds.vxMetersPerSecond, 1374 Speeds.vyMetersPerSecond, 1375 Speeds.omegaRadiansPerSecond, 1376 WheelForceFeedforwardsX, 1377 WheelForceFeedforwardsY, 1378 CenterOfRotation.getX(), 1379 CenterOfRotation.getY(), 1380 DriveRequestType.value, 1381 SteerRequestType.value, 1382 DesaturateWheelSpeeds, 1383 ForwardPerspective.value); 1384 } 1385 } 1386 1387 /** 1388 * Drives the swerve drivetrain in a field-centric manner, maintaining a 1389 * specified heading angle to ensure the robot is facing the desired direction 1390 * <p> 1391 * When users use this request, they specify the direction the robot should 1392 * travel oriented against the field, and the direction the robot should be facing. 1393 * <p> 1394 * An example scenario is that the robot is oriented to the east, the VelocityX 1395 * is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees. 1396 * In this scenario, the robot would drive northward at 5 m/s and turn clockwise 1397 * to a target of 180 degrees. 1398 * <p> 1399 * This control request is especially useful for autonomous control, where the 1400 * robot should be facing a changing direction throughout the motion. 1401 */ 1402 public static class FieldCentricFacingAngle implements SwerveRequest { 1403 /** 1404 * The velocity in the X direction, in m/s. 1405 * X is defined as forward according to WPILib convention, 1406 * so this determines how fast to travel forward. 1407 */ 1408 public double VelocityX = 0; 1409 /** 1410 * The velocity in the Y direction, in m/s. 1411 * Y is defined as to the left according to WPILib convention, 1412 * so this determines how fast to travel to the left. 1413 */ 1414 public double VelocityY = 0; 1415 /** 1416 * The desired direction to face. 1417 * 0 Degrees is defined as in the direction of the X axis. 1418 * As a result, a TargetDirection of 90 degrees will point along 1419 * the Y axis, or to the left. 1420 */ 1421 public Rotation2d TargetDirection = new Rotation2d(); 1422 /** 1423 * The rotational rate feedforward to add to the output of the heading 1424 * controller, in radians per second. When using a motion profile for the 1425 * target direction, this can be set to the current velocity reference of 1426 * the profile. 1427 */ 1428 public double TargetRateFeedforward = 0; 1429 1430 /** 1431 * The allowable deadband of the request, in m/s. 1432 */ 1433 public double Deadband = 0; 1434 /** 1435 * The rotational deadband of the request, in radians per second. 1436 */ 1437 public double RotationalDeadband = 0; 1438 /** 1439 * The maximum absolute rotational rate to allow, in radians per second. 1440 * Setting this to 0 results in no cap to rotational rate. 1441 */ 1442 public double MaxAbsRotationalRate = 0; 1443 /** 1444 * The center of rotation the robot should rotate around. 1445 * This is (0,0) by default, which will rotate around the center of the robot. 1446 */ 1447 public Translation2d CenterOfRotation = new Translation2d(); 1448 1449 /** 1450 * The type of control request to use for the drive motor. 1451 */ 1452 public SwerveModule.DriveRequestType DriveRequestType = SwerveModule.DriveRequestType.OpenLoopVoltage; 1453 /** 1454 * The type of control request to use for the steer motor. 1455 */ 1456 public SwerveModule.SteerRequestType SteerRequestType = SwerveModule.SteerRequestType.Position; 1457 /** 1458 * Whether to desaturate wheel speeds before applying. 1459 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 1460 */ 1461 public boolean DesaturateWheelSpeeds = true; 1462 1463 /** 1464 * The perspective to use when determining which direction is forward. 1465 */ 1466 public ForwardPerspectiveValue ForwardPerspective = ForwardPerspectiveValue.OperatorPerspective; 1467 /** 1468 * The perspective to use when determining which direction is forward for the 1469 * {@link #TargetDirection}. This allows for the heading control to use a different 1470 * perspective from the translation control. 1471 */ 1472 public TargetDirectionPerspectiveValue TargetDirectionPerspective = TargetDirectionPerspectiveValue.UseForwardPerspective; 1473 1474 /** 1475 * The PID controller used to maintain the desired heading. 1476 * Users can specify the PID gains to change how aggressively to maintain 1477 * heading. 1478 * <p> 1479 * This PID controller operates on heading radians and outputs a target 1480 * rotational rate in radians per second. Note that continuous input should 1481 * be enabled on the range [-pi, pi]. 1482 */ 1483 public PhoenixPIDController HeadingController = new PhoenixPIDController(0, 0, 0); 1484 1485 private final FieldCentric m_fieldCentric = new FieldCentric(); 1486 1487 public FieldCentricFacingAngle() { 1488 HeadingController.enableContinuousInput(-Math.PI, Math.PI); 1489 } 1490 1491 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 1492 Rotation2d angleToFace = TargetDirection; 1493 if ( 1494 TargetDirectionPerspective == TargetDirectionPerspectiveValue.UseForwardPerspective && 1495 ForwardPerspective == ForwardPerspectiveValue.OperatorPerspective 1496 ) { 1497 /* If we're operator perspective, rotate the direction we want to face by the angle */ 1498 angleToFace = angleToFace.rotateBy(parameters.operatorForwardDirection); 1499 } 1500 1501 double toApplyOmega = TargetRateFeedforward + 1502 HeadingController.calculate( 1503 parameters.currentPose.getRotation().getRadians(), 1504 angleToFace.getRadians(), 1505 parameters.timestamp 1506 ); 1507 if (MaxAbsRotationalRate > 0.0) { 1508 if (toApplyOmega > MaxAbsRotationalRate) { 1509 toApplyOmega = MaxAbsRotationalRate; 1510 } else if (toApplyOmega < -MaxAbsRotationalRate) { 1511 toApplyOmega = -MaxAbsRotationalRate; 1512 } 1513 } 1514 1515 return m_fieldCentric 1516 .withVelocityX(VelocityX) 1517 .withVelocityY(VelocityY) 1518 .withRotationalRate(toApplyOmega) 1519 .withDeadband(Deadband) 1520 .withRotationalDeadband(RotationalDeadband) 1521 .withCenterOfRotation(CenterOfRotation) 1522 .withDriveRequestType(DriveRequestType) 1523 .withSteerRequestType(SteerRequestType) 1524 .withDesaturateWheelSpeeds(DesaturateWheelSpeeds) 1525 .withForwardPerspective(ForwardPerspective) 1526 .apply(parameters, modulesToApply); 1527 } 1528 1529 /** 1530 * Modifies the PID gains of the HeadingController parameter and returns itself. 1531 * <p> 1532 * Sets the proportional, integral, and differential coefficients used to maintain 1533 * the desired heading. Users can specify the PID gains to change how aggressively to 1534 * maintain heading. 1535 * <p> 1536 * This PID controller operates on heading radians and outputs a target 1537 * rotational rate in radians per second. 1538 * 1539 * @param kP The proportional coefficient; must be >= 0 1540 * @param kI The integral coefficient; must be >= 0 1541 * @param kD The differential coefficient; must be >= 0 1542 * @return this object 1543 */ 1544 public FieldCentricFacingAngle withHeadingPID(double kP, double kI, double kD) 1545 { 1546 this.HeadingController.setPID(kP, kI, kD); 1547 return this; 1548 } 1549 1550 /** 1551 * Modifies the VelocityX parameter and returns itself. 1552 * <p> 1553 * The velocity in the X direction, in m/s. X is defined as forward according to 1554 * WPILib convention, so this determines how fast to travel forward. 1555 * 1556 * @param newVelocityX Parameter to modify 1557 * @return this object 1558 */ 1559 public FieldCentricFacingAngle withVelocityX(double newVelocityX) { 1560 this.VelocityX = newVelocityX; 1561 return this; 1562 } 1563 1564 /** 1565 * Modifies the VelocityX parameter and returns itself. 1566 * <p> 1567 * The velocity in the X direction, in m/s. X is defined as forward according to 1568 * WPILib convention, so this determines how fast to travel forward. 1569 * 1570 * @param newVelocityX Parameter to modify 1571 * @return this object 1572 */ 1573 public FieldCentricFacingAngle withVelocityX(LinearVelocity newVelocityX) { 1574 this.VelocityX = newVelocityX.in(MetersPerSecond); 1575 return this; 1576 } 1577 1578 /** 1579 * Modifies the VelocityY parameter and returns itself. 1580 * <p> 1581 * The velocity in the Y direction, in m/s. Y is defined as to the left 1582 * according to WPILib convention, so this determines how fast to travel to the 1583 * left. 1584 * 1585 * @param newVelocityY Parameter to modify 1586 * @return this object 1587 */ 1588 public FieldCentricFacingAngle withVelocityY(double newVelocityY) { 1589 this.VelocityY = newVelocityY; 1590 return this; 1591 } 1592 1593 /** 1594 * Modifies the VelocityY parameter and returns itself. 1595 * <p> 1596 * The velocity in the Y direction, in m/s. Y is defined as to the left 1597 * according to WPILib convention, so this determines how fast to travel to the 1598 * left. 1599 * 1600 * @param newVelocityY Parameter to modify 1601 * @return this object 1602 */ 1603 public FieldCentricFacingAngle withVelocityY(LinearVelocity newVelocityY) { 1604 this.VelocityY = newVelocityY.in(MetersPerSecond); 1605 return this; 1606 } 1607 1608 /** 1609 * Modifies the TargetDirection parameter and returns itself. 1610 * <p> 1611 * The desired direction to face. 0 Degrees is defined as in the direction of 1612 * the X axis. As a result, a TargetDirection of 90 degrees will point along 1613 * the Y axis, or to the left. 1614 * 1615 * @param newTargetDirection Parameter to modify 1616 * @return this object 1617 */ 1618 public FieldCentricFacingAngle withTargetDirection(Rotation2d newTargetDirection) { 1619 this.TargetDirection = newTargetDirection; 1620 return this; 1621 } 1622 1623 /** 1624 * Modifies the TargetRateFeedforward parameter and returns itself. 1625 * <p> 1626 * The rotational rate feedforward to add to the output of the heading 1627 * controller, in radians per second. When using a motion profile for the 1628 * target direction, this can be set to the current velocity reference of 1629 * the profile. 1630 * 1631 * @param newTargetRateFeedforward Parameter to modify 1632 * @return this object 1633 */ 1634 public FieldCentricFacingAngle withTargetRateFeedforward(double newTargetRateFeedforward) { 1635 this.TargetRateFeedforward = newTargetRateFeedforward; 1636 return this; 1637 } 1638 /** 1639 * Modifies the TargetRateFeedforward parameter and returns itself. 1640 * <p> 1641 * The rotational rate feedforward to add to the output of the heading 1642 * controller, in radians per second. When using a motion profile for the 1643 * target direction, this can be set to the current velocity reference of 1644 * the profile. 1645 * 1646 * @param newTargetRateFeedforward Parameter to modify 1647 * @return this object 1648 */ 1649 public FieldCentricFacingAngle withTargetRateFeedforward(AngularVelocity newTargetRateFeedforward) { 1650 this.TargetRateFeedforward = newTargetRateFeedforward.in(RadiansPerSecond); 1651 return this; 1652 } 1653 1654 /** 1655 * Modifies the Deadband parameter and returns itself. 1656 * <p> 1657 * The allowable deadband of the request, in m/s. 1658 * 1659 * @param newDeadband Parameter to modify 1660 * @return this object 1661 */ 1662 public FieldCentricFacingAngle withDeadband(double newDeadband) { 1663 this.Deadband = newDeadband; 1664 return this; 1665 } 1666 1667 /** 1668 * Modifies the Deadband parameter and returns itself. 1669 * <p> 1670 * The allowable deadband of the request, in m/s. 1671 * 1672 * @param newDeadband Parameter to modify 1673 * @return this object 1674 */ 1675 public FieldCentricFacingAngle withDeadband(LinearVelocity newDeadband) { 1676 this.Deadband = newDeadband.in(MetersPerSecond); 1677 return this; 1678 } 1679 1680 /** 1681 * Modifies the RotationalDeadband parameter and returns itself. 1682 * <p> 1683 * The rotational deadband of the request, in radians per second. 1684 * 1685 * @param newRotationalDeadband Parameter to modify 1686 * @return this object 1687 */ 1688 public FieldCentricFacingAngle withRotationalDeadband(double newRotationalDeadband) { 1689 this.RotationalDeadband = newRotationalDeadband; 1690 return this; 1691 } 1692 1693 /** 1694 * Modifies the RotationalDeadband parameter and returns itself. 1695 * <p> 1696 * The rotational deadband of the request, in radians per second. 1697 * 1698 * @param newRotationalDeadband Parameter to modify 1699 * @return this object 1700 */ 1701 public FieldCentricFacingAngle withRotationalDeadband(AngularVelocity newRotationalDeadband) { 1702 this.RotationalDeadband = newRotationalDeadband.in(RadiansPerSecond); 1703 return this; 1704 } 1705 1706 /** 1707 * Modifies the MaxAbsRotationalRate parameter and returns itself. 1708 * <p> 1709 * The maximum absolute rotational rate to allow, in radians per second. 1710 * Setting this to 0 results in no cap to rotational rate. 1711 * 1712 * @param newMaxAbsRotationalRate Parameter to modify 1713 * @return this object 1714 */ 1715 public FieldCentricFacingAngle withMaxAbsRotationalRate(double newMaxAbsRotationalRate) { 1716 this.MaxAbsRotationalRate = newMaxAbsRotationalRate; 1717 return this; 1718 } 1719 1720 /** 1721 * Modifies the MaxAbsRotationalRate parameter and returns itself. 1722 * <p> 1723 * The maximum absolute rotational rate to allow, in radians per second. 1724 * Setting this to 0 results in no cap to rotational rate. 1725 * 1726 * @param newMaxAbsRotationalRate Parameter to modify 1727 * @return this object 1728 */ 1729 public FieldCentricFacingAngle withMaxAbsRotationalRate(AngularVelocity newMaxAbsRotationalRate) { 1730 this.MaxAbsRotationalRate = newMaxAbsRotationalRate.in(RadiansPerSecond); 1731 return this; 1732 } 1733 1734 /** 1735 * Modifies the CenterOfRotation parameter and returns itself. 1736 * <p> 1737 * The center of rotation the robot should rotate around. This is (0,0) by 1738 * default, which will rotate around the center of the robot. 1739 * 1740 * @param newCenterOfRotation Parameter to modify 1741 * @return this object 1742 */ 1743 public FieldCentricFacingAngle withCenterOfRotation(Translation2d newCenterOfRotation) { 1744 this.CenterOfRotation = newCenterOfRotation; 1745 return this; 1746 } 1747 1748 /** 1749 * Modifies the DriveRequestType parameter and returns itself. 1750 * <p> 1751 * The type of control request to use for the drive motor. 1752 * 1753 * @param newDriveRequestType Parameter to modify 1754 * @return this object 1755 */ 1756 public FieldCentricFacingAngle withDriveRequestType(SwerveModule.DriveRequestType newDriveRequestType) { 1757 this.DriveRequestType = newDriveRequestType; 1758 return this; 1759 } 1760 1761 /** 1762 * Modifies the SteerRequestType parameter and returns itself. 1763 * <p> 1764 * The type of control request to use for the drive motor. 1765 * 1766 * @param newSteerRequestType Parameter to modify 1767 * @return this object 1768 */ 1769 public FieldCentricFacingAngle withSteerRequestType(SwerveModule.SteerRequestType newSteerRequestType) { 1770 this.SteerRequestType = newSteerRequestType; 1771 return this; 1772 } 1773 1774 /** 1775 * Modifies the DesaturateWheelSpeeds parameter and returns itself. 1776 * <p> 1777 * Whether to desaturate wheel speeds before applying. For more information, see 1778 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 1779 * 1780 * @param newDesaturateWheelSpeeds Parameter to modify 1781 * @return this object 1782 */ 1783 public FieldCentricFacingAngle withDesaturateWheelSpeeds(boolean newDesaturateWheelSpeeds) { 1784 this.DesaturateWheelSpeeds = newDesaturateWheelSpeeds; 1785 return this; 1786 } 1787 1788 /** 1789 * Modifies the ForwardPerspective parameter and returns itself. 1790 * <p> 1791 * The perspective to use when determining which direction is forward. 1792 * 1793 * @param newForwardPerspective Parameter to modify 1794 * @return this object 1795 */ 1796 public FieldCentricFacingAngle withForwardPerspective(ForwardPerspectiveValue newForwardPerspective) { 1797 this.ForwardPerspective = newForwardPerspective; 1798 return this; 1799 } 1800 1801 /** 1802 * Modifies the TargetDirectionPerspective parameter and returns itself. 1803 * <p> 1804 * The perspective to use when determining which direction is forward for the 1805 * {@link #TargetDirection}. This allows for the heading control to use a different 1806 * perspective from the translation control. 1807 * 1808 * @param newTargetDirectionPerspective Parameter to modify 1809 * @return this object 1810 */ 1811 public FieldCentricFacingAngle withTargetDirectionPerspective(TargetDirectionPerspectiveValue newTargetDirectionPerspective) { 1812 this.TargetDirectionPerspective = newTargetDirectionPerspective; 1813 return this; 1814 } 1815 } 1816 1817 /** 1818 * Drives the swerve drivetrain in a robot-centric manner, maintaining a 1819 * specified heading angle to ensure the robot is facing the desired direction 1820 * <p> 1821 * When users use this request, they specify the direction the robot should 1822 * travel oriented against the robot itself, and the direction the robot should 1823 * be facing relative to the field. 1824 * <p> 1825 * An example scenario is that the robot is oriented to the east, the VelocityX 1826 * is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees. 1827 * In this scenario, the robot would drive forward at 5 m/s and turn clockwise 1828 * to a target of 180 degrees. 1829 * <p> 1830 * This control request is especially useful for vision control, where the 1831 * robot should be facing a vision target throughout the motion. 1832 */ 1833 public static class RobotCentricFacingAngle implements SwerveRequest { 1834 /** 1835 * The velocity in the X direction, in m/s. 1836 * X is defined as forward according to WPILib convention, 1837 * so this determines how fast to travel forward. 1838 */ 1839 public double VelocityX = 0; 1840 /** 1841 * The velocity in the Y direction, in m/s. 1842 * Y is defined as to the left according to WPILib convention, 1843 * so this determines how fast to travel to the left. 1844 */ 1845 public double VelocityY = 0; 1846 /** 1847 * The desired direction to face. 1848 * 0 Degrees is defined as in the direction of the X axis. 1849 * As a result, a TargetDirection of 90 degrees will point along 1850 * the Y axis, or to the left. 1851 */ 1852 public Rotation2d TargetDirection = new Rotation2d(); 1853 /** 1854 * The rotational rate feedforward to add to the output of the heading 1855 * controller, in radians per second. When using a motion profile for the 1856 * target direction, this can be set to the current velocity reference of 1857 * the profile. 1858 */ 1859 public double TargetRateFeedforward = 0; 1860 1861 /** 1862 * The allowable deadband of the request, in m/s. 1863 */ 1864 public double Deadband = 0; 1865 /** 1866 * The rotational deadband of the request, in radians per second. 1867 */ 1868 public double RotationalDeadband = 0; 1869 /** 1870 * The maximum absolute rotational rate to allow, in radians per second. 1871 * Setting this to 0 results in no cap to rotational rate. 1872 */ 1873 public double MaxAbsRotationalRate = 0; 1874 /** 1875 * The center of rotation the robot should rotate around. 1876 * This is (0,0) by default, which will rotate around the center of the robot. 1877 */ 1878 public Translation2d CenterOfRotation = new Translation2d(); 1879 1880 /** 1881 * The type of control request to use for the drive motor. 1882 */ 1883 public SwerveModule.DriveRequestType DriveRequestType = SwerveModule.DriveRequestType.OpenLoopVoltage; 1884 /** 1885 * The type of control request to use for the steer motor. 1886 */ 1887 public SwerveModule.SteerRequestType SteerRequestType = SwerveModule.SteerRequestType.Position; 1888 /** 1889 * Whether to desaturate wheel speeds before applying. 1890 * For more information, see the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 1891 */ 1892 public boolean DesaturateWheelSpeeds = true; 1893 1894 /** 1895 * The perspective to use when determining which direction is forward 1896 * for the target heading. 1897 */ 1898 public ForwardPerspectiveValue ForwardPerspective = ForwardPerspectiveValue.OperatorPerspective; 1899 1900 /** 1901 * The PID controller used to maintain the desired heading. 1902 * Users can specify the PID gains to change how aggressively to maintain 1903 * heading. 1904 * <p> 1905 * This PID controller operates on heading radians and outputs a target 1906 * rotational rate in radians per second. Note that continuous input should 1907 * be enabled on the range [-pi, pi]. 1908 */ 1909 public PhoenixPIDController HeadingController = new PhoenixPIDController(0, 0, 0); 1910 1911 private final RobotCentric m_robotCentric = new RobotCentric(); 1912 1913 public RobotCentricFacingAngle() { 1914 HeadingController.enableContinuousInput(-Math.PI, Math.PI); 1915 } 1916 1917 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 1918 Rotation2d angleToFace = TargetDirection; 1919 if (ForwardPerspective == ForwardPerspectiveValue.OperatorPerspective) { 1920 /* If we're operator perspective, rotate the direction we want to face by the angle */ 1921 angleToFace = angleToFace.rotateBy(parameters.operatorForwardDirection); 1922 } 1923 1924 double toApplyOmega = TargetRateFeedforward + 1925 HeadingController.calculate( 1926 parameters.currentPose.getRotation().getRadians(), 1927 angleToFace.getRadians(), 1928 parameters.timestamp 1929 ); 1930 if (MaxAbsRotationalRate > 0.0) { 1931 if (toApplyOmega > MaxAbsRotationalRate) { 1932 toApplyOmega = MaxAbsRotationalRate; 1933 } else if (toApplyOmega < -MaxAbsRotationalRate) { 1934 toApplyOmega = -MaxAbsRotationalRate; 1935 } 1936 } 1937 1938 return m_robotCentric 1939 .withVelocityX(VelocityX) 1940 .withVelocityY(VelocityY) 1941 .withRotationalRate(toApplyOmega) 1942 .withDeadband(Deadband) 1943 .withRotationalDeadband(RotationalDeadband) 1944 .withCenterOfRotation(CenterOfRotation) 1945 .withDriveRequestType(DriveRequestType) 1946 .withSteerRequestType(SteerRequestType) 1947 .withDesaturateWheelSpeeds(DesaturateWheelSpeeds) 1948 .apply(parameters, modulesToApply); 1949 } 1950 1951 /** 1952 * Modifies the PID gains of the HeadingController parameter and returns itself. 1953 * <p> 1954 * Sets the proportional, integral, and differential coefficients used to maintain 1955 * the desired heading. Users can specify the PID gains to change how aggressively to 1956 * maintain heading. 1957 * <p> 1958 * This PID controller operates on heading radians and outputs a target 1959 * rotational rate in radians per second. 1960 * 1961 * @param kP The proportional coefficient; must be >= 0 1962 * @param kI The integral coefficient; must be >= 0 1963 * @param kD The differential coefficient; must be >= 0 1964 * @return this object 1965 */ 1966 public RobotCentricFacingAngle withHeadingPID(double kP, double kI, double kD) 1967 { 1968 this.HeadingController.setPID(kP, kI, kD); 1969 return this; 1970 } 1971 1972 /** 1973 * Modifies the VelocityX parameter and returns itself. 1974 * <p> 1975 * The velocity in the X direction, in m/s. X is defined as forward according to 1976 * WPILib convention, so this determines how fast to travel forward. 1977 * 1978 * @param newVelocityX Parameter to modify 1979 * @return this object 1980 */ 1981 public RobotCentricFacingAngle withVelocityX(double newVelocityX) { 1982 this.VelocityX = newVelocityX; 1983 return this; 1984 } 1985 1986 /** 1987 * Modifies the VelocityX parameter and returns itself. 1988 * <p> 1989 * The velocity in the X direction, in m/s. X is defined as forward according to 1990 * WPILib convention, so this determines how fast to travel forward. 1991 * 1992 * @param newVelocityX Parameter to modify 1993 * @return this object 1994 */ 1995 public RobotCentricFacingAngle withVelocityX(LinearVelocity newVelocityX) { 1996 this.VelocityX = newVelocityX.in(MetersPerSecond); 1997 return this; 1998 } 1999 2000 /** 2001 * Modifies the VelocityY parameter and returns itself. 2002 * <p> 2003 * The velocity in the Y direction, in m/s. Y is defined as to the left 2004 * according to WPILib convention, so this determines how fast to travel to the 2005 * left. 2006 * 2007 * @param newVelocityY Parameter to modify 2008 * @return this object 2009 */ 2010 public RobotCentricFacingAngle withVelocityY(double newVelocityY) { 2011 this.VelocityY = newVelocityY; 2012 return this; 2013 } 2014 2015 /** 2016 * Modifies the VelocityY parameter and returns itself. 2017 * <p> 2018 * The velocity in the Y direction, in m/s. Y is defined as to the left 2019 * according to WPILib convention, so this determines how fast to travel to the 2020 * left. 2021 * 2022 * @param newVelocityY Parameter to modify 2023 * @return this object 2024 */ 2025 public RobotCentricFacingAngle withVelocityY(LinearVelocity newVelocityY) { 2026 this.VelocityY = newVelocityY.in(MetersPerSecond); 2027 return this; 2028 } 2029 2030 /** 2031 * Modifies the TargetDirection parameter and returns itself. 2032 * <p> 2033 * The desired direction to face. 0 Degrees is defined as in the direction of 2034 * the X axis. As a result, a TargetDirection of 90 degrees will point along 2035 * the Y axis, or to the left. 2036 * 2037 * @param newTargetDirection Parameter to modify 2038 * @return this object 2039 */ 2040 public RobotCentricFacingAngle withTargetDirection(Rotation2d newTargetDirection) { 2041 this.TargetDirection = newTargetDirection; 2042 return this; 2043 } 2044 2045 /** 2046 * Modifies the TargetRateFeedforward parameter and returns itself. 2047 * <p> 2048 * The rotational rate feedforward to add to the output of the heading 2049 * controller, in radians per second. When using a motion profile for the 2050 * target direction, this can be set to the current velocity reference of 2051 * the profile. 2052 * 2053 * @param newTargetRateFeedforward Parameter to modify 2054 * @return this object 2055 */ 2056 public RobotCentricFacingAngle withTargetRateFeedforward(double newTargetRateFeedforward) { 2057 this.TargetRateFeedforward = newTargetRateFeedforward; 2058 return this; 2059 } 2060 /** 2061 * Modifies the TargetRateFeedforward parameter and returns itself. 2062 * <p> 2063 * The rotational rate feedforward to add to the output of the heading 2064 * controller, in radians per second. When using a motion profile for the 2065 * target direction, this can be set to the current velocity reference of 2066 * the profile. 2067 * 2068 * @param newTargetRateFeedforward Parameter to modify 2069 * @return this object 2070 */ 2071 public RobotCentricFacingAngle withTargetRateFeedforward(AngularVelocity newTargetRateFeedforward) { 2072 this.TargetRateFeedforward = newTargetRateFeedforward.in(RadiansPerSecond); 2073 return this; 2074 } 2075 2076 /** 2077 * Modifies the Deadband parameter and returns itself. 2078 * <p> 2079 * The allowable deadband of the request, in m/s. 2080 * 2081 * @param newDeadband Parameter to modify 2082 * @return this object 2083 */ 2084 public RobotCentricFacingAngle withDeadband(double newDeadband) { 2085 this.Deadband = newDeadband; 2086 return this; 2087 } 2088 2089 /** 2090 * Modifies the Deadband parameter and returns itself. 2091 * <p> 2092 * The allowable deadband of the request, in m/s. 2093 * 2094 * @param newDeadband Parameter to modify 2095 * @return this object 2096 */ 2097 public RobotCentricFacingAngle withDeadband(LinearVelocity newDeadband) { 2098 this.Deadband = newDeadband.in(MetersPerSecond); 2099 return this; 2100 } 2101 2102 /** 2103 * Modifies the RotationalDeadband parameter and returns itself. 2104 * <p> 2105 * The rotational deadband of the request, in radians per second. 2106 * 2107 * @param newRotationalDeadband Parameter to modify 2108 * @return this object 2109 */ 2110 public RobotCentricFacingAngle withRotationalDeadband(double newRotationalDeadband) { 2111 this.RotationalDeadband = newRotationalDeadband; 2112 return this; 2113 } 2114 2115 /** 2116 * Modifies the RotationalDeadband parameter and returns itself. 2117 * <p> 2118 * The rotational deadband of the request, in radians per second. 2119 * 2120 * @param newRotationalDeadband Parameter to modify 2121 * @return this object 2122 */ 2123 public RobotCentricFacingAngle withRotationalDeadband(AngularVelocity newRotationalDeadband) { 2124 this.RotationalDeadband = newRotationalDeadband.in(RadiansPerSecond); 2125 return this; 2126 } 2127 2128 /** 2129 * Modifies the MaxAbsRotationalRate parameter and returns itself. 2130 * <p> 2131 * The maximum absolute rotational rate to allow, in radians per second. 2132 * Setting this to 0 results in no cap to rotational rate. 2133 * 2134 * @param newMaxAbsRotationalRate Parameter to modify 2135 * @return this object 2136 */ 2137 public RobotCentricFacingAngle withMaxAbsRotationalRate(double newMaxAbsRotationalRate) { 2138 this.MaxAbsRotationalRate = newMaxAbsRotationalRate; 2139 return this; 2140 } 2141 2142 /** 2143 * Modifies the MaxAbsRotationalRate parameter and returns itself. 2144 * <p> 2145 * The maximum absolute rotational rate to allow, in radians per second. 2146 * Setting this to 0 results in no cap to rotational rate. 2147 * 2148 * @param newMaxAbsRotationalRate Parameter to modify 2149 * @return this object 2150 */ 2151 public RobotCentricFacingAngle withMaxAbsRotationalRate(AngularVelocity newMaxAbsRotationalRate) { 2152 this.MaxAbsRotationalRate = newMaxAbsRotationalRate.in(RadiansPerSecond); 2153 return this; 2154 } 2155 2156 /** 2157 * Modifies the CenterOfRotation parameter and returns itself. 2158 * <p> 2159 * The center of rotation the robot should rotate around. This is (0,0) by 2160 * default, which will rotate around the center of the robot. 2161 * 2162 * @param newCenterOfRotation Parameter to modify 2163 * @return this object 2164 */ 2165 public RobotCentricFacingAngle withCenterOfRotation(Translation2d newCenterOfRotation) { 2166 this.CenterOfRotation = newCenterOfRotation; 2167 return this; 2168 } 2169 2170 /** 2171 * Modifies the DriveRequestType parameter and returns itself. 2172 * <p> 2173 * The type of control request to use for the drive motor. 2174 * 2175 * @param newDriveRequestType Parameter to modify 2176 * @return this object 2177 */ 2178 public RobotCentricFacingAngle withDriveRequestType(SwerveModule.DriveRequestType newDriveRequestType) { 2179 this.DriveRequestType = newDriveRequestType; 2180 return this; 2181 } 2182 2183 /** 2184 * Modifies the SteerRequestType parameter and returns itself. 2185 * <p> 2186 * The type of control request to use for the drive motor. 2187 * 2188 * @param newSteerRequestType Parameter to modify 2189 * @return this object 2190 */ 2191 public RobotCentricFacingAngle withSteerRequestType(SwerveModule.SteerRequestType newSteerRequestType) { 2192 this.SteerRequestType = newSteerRequestType; 2193 return this; 2194 } 2195 2196 /** 2197 * Modifies the DesaturateWheelSpeeds parameter and returns itself. 2198 * <p> 2199 * Whether to desaturate wheel speeds before applying. For more information, see 2200 * the documentation of {@link SwerveDriveKinematics#desaturateWheelSpeeds}. 2201 * 2202 * @param newDesaturateWheelSpeeds Parameter to modify 2203 * @return this object 2204 */ 2205 public RobotCentricFacingAngle withDesaturateWheelSpeeds(boolean newDesaturateWheelSpeeds) { 2206 this.DesaturateWheelSpeeds = newDesaturateWheelSpeeds; 2207 return this; 2208 } 2209 2210 /** 2211 * Modifies the ForwardPerspective parameter and returns itself. 2212 * <p> 2213 * The perspective to use when determining which direction is forward 2214 * for the target heading. 2215 * 2216 * @param newForwardPerspective Parameter to modify 2217 * @return this object 2218 */ 2219 public RobotCentricFacingAngle withForwardPerspective(ForwardPerspectiveValue newForwardPerspective) { 2220 this.ForwardPerspective = newForwardPerspective; 2221 return this; 2222 } 2223 } 2224 2225 /** 2226 * SysId-specific SwerveRequest to characterize the translational 2227 * characteristics of a swerve drivetrain. 2228 */ 2229 public static class SysIdSwerveTranslation implements SwerveRequest { 2230 /** 2231 * Voltage to apply to drive wheels. 2232 */ 2233 public double VoltsToApply = 0; 2234 2235 /** Local reference to a voltage request for the drive motors */ 2236 private final VoltageOut m_driveRequest = new VoltageOut(0); 2237 /** Local reference to a position voltage request for the steer motors */ 2238 private final PositionVoltage m_steerRequest_Voltage = new PositionVoltage(0); 2239 /** Local reference to a position torque current request for the steer motors */ 2240 private final PositionTorqueCurrentFOC m_steerRequest_TorqueCurrent = new PositionTorqueCurrentFOC(0); 2241 2242 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 2243 for (int i = 0; i < modulesToApply.length; ++i) { 2244 switch (modulesToApply[i].getSteerClosedLoopOutputType()) { 2245 case Voltage: 2246 modulesToApply[i].apply( 2247 m_driveRequest.withOutput(VoltsToApply), 2248 m_steerRequest_Voltage.withPosition(0) 2249 ); 2250 break; 2251 case TorqueCurrentFOC: 2252 modulesToApply[i].apply( 2253 m_driveRequest.withOutput(VoltsToApply), 2254 m_steerRequest_TorqueCurrent.withPosition(0) 2255 ); 2256 break; 2257 } 2258 } 2259 return StatusCode.OK; 2260 } 2261 2262 /** 2263 * Sets the voltage to apply to the drive wheels. 2264 * 2265 * @param volts Voltage to apply 2266 * @return this request 2267 */ 2268 public SysIdSwerveTranslation withVolts(double volts) { 2269 VoltsToApply = volts; 2270 return this; 2271 } 2272 /** 2273 * Sets the voltage to apply to the drive wheels. 2274 * 2275 * @param volts Voltage to apply 2276 * @return this request 2277 */ 2278 public SysIdSwerveTranslation withVolts(Voltage volts) { 2279 VoltsToApply = volts.in(Volts); 2280 return this; 2281 } 2282 } 2283 2284 /** 2285 * SysId-specific SwerveRequest to characterize the rotational 2286 * characteristics of a swerve drivetrain. This is useful to 2287 * characterize the heading controller for FieldCentricFacingAngle. 2288 * <p> 2289 * The RotationalRate of this swerve request should be logged. 2290 * When importing the log to SysId, set the "voltage" to 2291 * RotationalRate, "position" to the Pigeon 2 Yaw, and "velocity" 2292 * to the Pigeon 2 AngularVelocityZWorld. Note that the position 2293 * and velocity will both need to be scaled by pi/180. 2294 * <p> 2295 * Alternatively, the MotorVoltage of one of the drive motors can 2296 * be loaded into the SysId "voltage" field, which can be useful 2297 * when determining the MOI of the robot. 2298 */ 2299 public static class SysIdSwerveRotation implements SwerveRequest { 2300 /** 2301 * The angular rate to rotate at, in radians per second. 2302 */ 2303 public double RotationalRate = 0; 2304 2305 /** Local reference to a voltage request for the drive motors */ 2306 private final VoltageOut m_driveRequest = new VoltageOut(0); 2307 /** Local reference to a position voltage request for the steer motors */ 2308 private final PositionVoltage m_steerRequest_Voltage = new PositionVoltage(0); 2309 /** Local reference to a position torque current request for the steer motors */ 2310 private final PositionTorqueCurrentFOC m_steerRequest_TorqueCurrent = new PositionTorqueCurrentFOC(0); 2311 2312 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 2313 for (int i = 0; i < modulesToApply.length; ++i) { 2314 var speedMps = RotationalRate * parameters.moduleLocations[i].getNorm(); 2315 var driveVoltage = speedMps / parameters.kMaxSpeedMps * 12.0; 2316 2317 var angle = parameters.moduleLocations[i].getAngle().plus(Rotation2d.kCCW_90deg); 2318 2319 switch (modulesToApply[i].getSteerClosedLoopOutputType()) { 2320 case Voltage: 2321 modulesToApply[i].apply( 2322 m_driveRequest.withOutput(driveVoltage), 2323 m_steerRequest_Voltage.withPosition(angle.getRotations()) 2324 ); 2325 break; 2326 case TorqueCurrentFOC: 2327 modulesToApply[i].apply( 2328 m_driveRequest.withOutput(driveVoltage), 2329 m_steerRequest_TorqueCurrent.withPosition(angle.getRotations()) 2330 ); 2331 break; 2332 } 2333 } 2334 return StatusCode.OK; 2335 } 2336 2337 /** 2338 * Update the angular rate to rotate at, in radians per second. 2339 * 2340 * @param newRotationalRate Angular rate to rotate at 2341 * @return this request 2342 */ 2343 public SysIdSwerveRotation withRotationalRate(double newRotationalRate) { 2344 RotationalRate = newRotationalRate; 2345 return this; 2346 } 2347 /** 2348 * Update the angular rate to rotate at. 2349 * 2350 * @param newRotationalRate The angular rate to rotate at 2351 * @return this request 2352 */ 2353 public SysIdSwerveRotation withRotationalRate(AngularVelocity newRotationalRate) { 2354 RotationalRate = newRotationalRate.in(RadiansPerSecond); 2355 return this; 2356 } 2357 } 2358 2359 /** 2360 * SysId-specific SwerveRequest to characterize the steer module 2361 * characteristics of a swerve drivetrain. 2362 */ 2363 public static class SysIdSwerveSteerGains implements SwerveRequest { 2364 /** 2365 * Voltage to apply to steer motors. 2366 */ 2367 public double VoltsToApply = 0; 2368 2369 /** Local reference to a coast request for the drive motors */ 2370 private final CoastOut m_driveRequest = new CoastOut(); 2371 /** Local reference to a voltage request for the steer motors */ 2372 private final VoltageOut m_steerRequest = new VoltageOut(0); 2373 2374 public StatusCode apply(SwerveControlParameters parameters, SwerveModule<?, ?, ?>... modulesToApply) { 2375 for (int i = 0; i < modulesToApply.length; ++i) { 2376 modulesToApply[i].apply(m_driveRequest, m_steerRequest.withOutput(VoltsToApply)); 2377 } 2378 return StatusCode.OK; 2379 } 2380 2381 /** 2382 * Sets the voltage to apply to the steer motors. 2383 * 2384 * @param volts Voltage to apply 2385 * @return this request 2386 */ 2387 public SysIdSwerveSteerGains withVolts(double volts) { 2388 VoltsToApply = volts; 2389 return this; 2390 } 2391 /** 2392 * Sets the voltage to apply to the steer motors. 2393 * 2394 * @param volts Voltage to apply 2395 * @return this request 2396 */ 2397 public SysIdSwerveSteerGains withVolts(Voltage volts) { 2398 VoltsToApply = volts.in(Volts); 2399 return this; 2400 } 2401 } 2402}