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