001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj2.command; 006 007import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; 008 009import edu.wpi.first.math.controller.HolonomicDriveController; 010import edu.wpi.first.math.controller.PIDController; 011import edu.wpi.first.math.controller.ProfiledPIDController; 012import edu.wpi.first.math.controller.SimpleMotorFeedforward; 013import edu.wpi.first.math.geometry.Pose2d; 014import edu.wpi.first.math.geometry.Rotation2d; 015import edu.wpi.first.math.kinematics.ChassisSpeeds; 016import edu.wpi.first.math.kinematics.MecanumDriveKinematics; 017import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages; 018import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds; 019import edu.wpi.first.math.trajectory.Trajectory; 020import edu.wpi.first.wpilibj.Timer; 021import java.util.function.Consumer; 022import java.util.function.Supplier; 023 024/** 025 * A command that uses two PID controllers ({@link PIDController}) and a ProfiledPIDController 026 * ({@link ProfiledPIDController}) to follow a trajectory {@link Trajectory} with a mecanum drive. 027 * 028 * <p>The command handles trajectory-following, Velocity PID calculations, and feedforwards 029 * internally. This is intended to be a more-or-less "complete solution" that can be used by teams 030 * without a great deal of controls expertise. 031 * 032 * <p>Advanced teams seeking more flexibility (for example, those who wish to use the onboard PID 033 * functionality of a "smart" motor controller) may use the secondary constructor that omits the PID 034 * and feedforward functionality, returning only the raw wheel speeds from the PID controllers. 035 * 036 * <p>The robot angle controller does not follow the angle given by the trajectory but rather goes 037 * to the angle given in the final state of the trajectory. 038 * 039 * <p>This class is provided by the NewCommands VendorDep 040 */ 041@SuppressWarnings("removal") 042public class MecanumControllerCommand extends Command { 043 private final Timer m_timer = new Timer(); 044 private final boolean m_usePID; 045 private final Trajectory m_trajectory; 046 private final Supplier<Pose2d> m_pose; 047 private final SimpleMotorFeedforward m_feedforward; 048 private final MecanumDriveKinematics m_kinematics; 049 private final HolonomicDriveController m_controller; 050 private final Supplier<Rotation2d> m_desiredRotation; 051 private final double m_maxWheelVelocityMetersPerSecond; 052 private final PIDController m_frontLeftController; 053 private final PIDController m_rearLeftController; 054 private final PIDController m_frontRightController; 055 private final PIDController m_rearRightController; 056 private final Supplier<MecanumDriveWheelSpeeds> m_currentWheelSpeeds; 057 private final MecanumVoltagesConsumer m_outputDriveVoltages; 058 private final Consumer<MecanumDriveWheelSpeeds> m_outputWheelSpeeds; 059 private double m_prevFrontLeftSpeedSetpoint; // m/s 060 private double m_prevRearLeftSpeedSetpoint; // m/s 061 private double m_prevFrontRightSpeedSetpoint; // m/s 062 private double m_prevRearRightSpeedSetpoint; // m/s 063 064 /** 065 * Constructs a new MecanumControllerCommand that when executed will follow the provided 066 * trajectory. PID control and feedforward are handled internally. Outputs are scaled from -12 to 067 * 12 as a voltage output to the motor. 068 * 069 * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path 070 * this is left to the user, since it is not appropriate for paths with nonstationary endstates. 071 * 072 * @param trajectory The trajectory to follow. 073 * @param pose A function that supplies the robot pose - use one of the odometry classes to 074 * provide this. 075 * @param feedforward The feedforward to use for the drivetrain. 076 * @param kinematics The kinematics for the robot drivetrain. 077 * @param xController The Trajectory Tracker PID controller for the robot's x position. 078 * @param yController The Trajectory Tracker PID controller for the robot's y position. 079 * @param thetaController The Trajectory Tracker PID controller for angle for the robot. 080 * @param desiredRotation The angle that the robot should be facing. This is sampled at each time 081 * step. 082 * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel. 083 * @param frontLeftController The front left wheel velocity PID. 084 * @param rearLeftController The rear left wheel velocity PID. 085 * @param frontRightController The front right wheel velocity PID. 086 * @param rearRightController The rear right wheel velocity PID. 087 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing the current wheel speeds. 088 * @param outputDriveVoltages A MecanumVoltagesConsumer that consumes voltages of mecanum motors. 089 * @param requirements The subsystems to require. 090 */ 091 @SuppressWarnings("this-escape") 092 public MecanumControllerCommand( 093 Trajectory trajectory, 094 Supplier<Pose2d> pose, 095 SimpleMotorFeedforward feedforward, 096 MecanumDriveKinematics kinematics, 097 PIDController xController, 098 PIDController yController, 099 ProfiledPIDController thetaController, 100 Supplier<Rotation2d> desiredRotation, 101 double maxWheelVelocityMetersPerSecond, 102 PIDController frontLeftController, 103 PIDController rearLeftController, 104 PIDController frontRightController, 105 PIDController rearRightController, 106 Supplier<MecanumDriveWheelSpeeds> currentWheelSpeeds, 107 MecanumVoltagesConsumer outputDriveVoltages, 108 Subsystem... requirements) { 109 m_trajectory = requireNonNullParam(trajectory, "trajectory", "MecanumControllerCommand"); 110 m_pose = requireNonNullParam(pose, "pose", "MecanumControllerCommand"); 111 m_feedforward = requireNonNullParam(feedforward, "feedforward", "MecanumControllerCommand"); 112 m_kinematics = requireNonNullParam(kinematics, "kinematics", "MecanumControllerCommand"); 113 114 m_controller = 115 new HolonomicDriveController( 116 requireNonNullParam(xController, "xController", "MecanumControllerCommand"), 117 requireNonNullParam(yController, "yController", "MecanumControllerCommand"), 118 requireNonNullParam(thetaController, "thetaController", "MecanumControllerCommand")); 119 120 m_desiredRotation = 121 requireNonNullParam(desiredRotation, "desiredRotation", "MecanumControllerCommand"); 122 123 m_maxWheelVelocityMetersPerSecond = maxWheelVelocityMetersPerSecond; 124 125 m_frontLeftController = 126 requireNonNullParam(frontLeftController, "frontLeftController", "MecanumControllerCommand"); 127 m_rearLeftController = 128 requireNonNullParam(rearLeftController, "rearLeftController", "MecanumControllerCommand"); 129 m_frontRightController = 130 requireNonNullParam( 131 frontRightController, "frontRightController", "MecanumControllerCommand"); 132 m_rearRightController = 133 requireNonNullParam(rearRightController, "rearRightController", "MecanumControllerCommand"); 134 135 m_currentWheelSpeeds = 136 requireNonNullParam(currentWheelSpeeds, "currentWheelSpeeds", "MecanumControllerCommand"); 137 138 m_outputDriveVoltages = 139 requireNonNullParam(outputDriveVoltages, "outputDriveVoltages", "MecanumControllerCommand"); 140 141 m_outputWheelSpeeds = null; 142 143 m_usePID = true; 144 145 addRequirements(requirements); 146 } 147 148 /** 149 * Constructs a new MecanumControllerCommand that when executed will follow the provided 150 * trajectory. PID control and feedforward are handled internally. Outputs are scaled from -12 to 151 * 12 as a voltage output to the motor. 152 * 153 * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path 154 * this is left to the user, since it is not appropriate for paths with nonstationary endstates. 155 * 156 * @param trajectory The trajectory to follow. 157 * @param pose A function that supplies the robot pose - use one of the odometry classes to 158 * provide this. 159 * @param feedforward The feedforward to use for the drivetrain. 160 * @param kinematics The kinematics for the robot drivetrain. 161 * @param xController The Trajectory Tracker PID controller for the robot's x position. 162 * @param yController The Trajectory Tracker PID controller for the robot's y position. 163 * @param thetaController The Trajectory Tracker PID controller for angle for the robot. 164 * @param desiredRotation The angle that the robot should be facing. This is sampled at each time 165 * step. 166 * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel. 167 * @param frontLeftController The front left wheel velocity PID. 168 * @param rearLeftController The rear left wheel velocity PID. 169 * @param frontRightController The front right wheel velocity PID. 170 * @param rearRightController The rear right wheel velocity PID. 171 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing the current wheel speeds. 172 * @param outputDriveVoltages A MecanumDriveMotorVoltages object containing the output motor 173 * voltages. 174 * @param requirements The subsystems to require. 175 * @deprecated Use {@link MecanumVoltagesConsumer} instead of {@code 176 * Consumer<MecanumDriveMotorVoltages}. 177 */ 178 @Deprecated(since = "2025", forRemoval = true) 179 public MecanumControllerCommand( 180 Trajectory trajectory, 181 Supplier<Pose2d> pose, 182 SimpleMotorFeedforward feedforward, 183 MecanumDriveKinematics kinematics, 184 PIDController xController, 185 PIDController yController, 186 ProfiledPIDController thetaController, 187 Supplier<Rotation2d> desiredRotation, 188 double maxWheelVelocityMetersPerSecond, 189 PIDController frontLeftController, 190 PIDController rearLeftController, 191 PIDController frontRightController, 192 PIDController rearRightController, 193 Supplier<MecanumDriveWheelSpeeds> currentWheelSpeeds, 194 Consumer<MecanumDriveMotorVoltages> outputDriveVoltages, 195 Subsystem... requirements) { 196 this( 197 trajectory, 198 pose, 199 feedforward, 200 kinematics, 201 xController, 202 yController, 203 thetaController, 204 desiredRotation, 205 maxWheelVelocityMetersPerSecond, 206 frontLeftController, 207 rearLeftController, 208 frontRightController, 209 rearRightController, 210 currentWheelSpeeds, 211 (frontLeft, frontRight, rearLeft, rearRight) -> 212 outputDriveVoltages.accept( 213 new MecanumDriveMotorVoltages(frontLeft, frontRight, rearLeft, rearRight)), 214 requirements); 215 } 216 217 /** 218 * Constructs a new MecanumControllerCommand that when executed will follow the provided 219 * trajectory. PID control and feedforward are handled internally. Outputs are scaled from -12 to 220 * 12 as a voltage output to the motor. 221 * 222 * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path 223 * this is left to the user, since it is not appropriate for paths with nonstationary endstates. 224 * 225 * <p>Note 2: The final rotation of the robot will be set to the rotation of the final pose in the 226 * trajectory. The robot will not follow the rotations from the poses at each timestep. If 227 * alternate rotation behavior is desired, the other constructor with a supplier for rotation 228 * should be used. 229 * 230 * @param trajectory The trajectory to follow. 231 * @param pose A function that supplies the robot pose - use one of the odometry classes to 232 * provide this. 233 * @param feedforward The feedforward to use for the drivetrain. 234 * @param kinematics The kinematics for the robot drivetrain. 235 * @param xController The Trajectory Tracker PID controller for the robot's x position. 236 * @param yController The Trajectory Tracker PID controller for the robot's y position. 237 * @param thetaController The Trajectory Tracker PID controller for angle for the robot. 238 * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel. 239 * @param frontLeftController The front left wheel velocity PID. 240 * @param rearLeftController The rear left wheel velocity PID. 241 * @param frontRightController The front right wheel velocity PID. 242 * @param rearRightController The rear right wheel velocity PID. 243 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing the current wheel speeds. 244 * @param outputDriveVoltages A MecanumVoltagesConsumer that consumes voltages of mecanum motors. 245 * @param requirements The subsystems to require. 246 */ 247 public MecanumControllerCommand( 248 Trajectory trajectory, 249 Supplier<Pose2d> pose, 250 SimpleMotorFeedforward feedforward, 251 MecanumDriveKinematics kinematics, 252 PIDController xController, 253 PIDController yController, 254 ProfiledPIDController thetaController, 255 double maxWheelVelocityMetersPerSecond, 256 PIDController frontLeftController, 257 PIDController rearLeftController, 258 PIDController frontRightController, 259 PIDController rearRightController, 260 Supplier<MecanumDriveWheelSpeeds> currentWheelSpeeds, 261 MecanumVoltagesConsumer outputDriveVoltages, 262 Subsystem... requirements) { 263 this( 264 trajectory, 265 pose, 266 feedforward, 267 kinematics, 268 xController, 269 yController, 270 thetaController, 271 () -> 272 trajectory.getStates().get(trajectory.getStates().size() - 1).poseMeters.getRotation(), 273 maxWheelVelocityMetersPerSecond, 274 frontLeftController, 275 rearLeftController, 276 frontRightController, 277 rearRightController, 278 currentWheelSpeeds, 279 outputDriveVoltages, 280 requirements); 281 } 282 283 /** 284 * Constructs a new MecanumControllerCommand that when executed will follow the provided 285 * trajectory. PID control and feedforward are handled internally. Outputs are scaled from -12 to 286 * 12 as a voltage output to the motor. 287 * 288 * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path 289 * this is left to the user, since it is not appropriate for paths with nonstationary endstates. 290 * 291 * <p>Note 2: The final rotation of the robot will be set to the rotation of the final pose in the 292 * trajectory. The robot will not follow the rotations from the poses at each timestep. If 293 * alternate rotation behavior is desired, the other constructor with a supplier for rotation 294 * should be used. 295 * 296 * @param trajectory The trajectory to follow. 297 * @param pose A function that supplies the robot pose - use one of the odometry classes to 298 * provide this. 299 * @param feedforward The feedforward to use for the drivetrain. 300 * @param kinematics The kinematics for the robot drivetrain. 301 * @param xController The Trajectory Tracker PID controller for the robot's x position. 302 * @param yController The Trajectory Tracker PID controller for the robot's y position. 303 * @param thetaController The Trajectory Tracker PID controller for angle for the robot. 304 * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel. 305 * @param frontLeftController The front left wheel velocity PID. 306 * @param rearLeftController The rear left wheel velocity PID. 307 * @param frontRightController The front right wheel velocity PID. 308 * @param rearRightController The rear right wheel velocity PID. 309 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing the current wheel speeds. 310 * @param outputDriveVoltages A MecanumDriveMotorVoltages object containing the output motor 311 * voltages. 312 * @param requirements The subsystems to require. 313 * @deprecated Use {@link MecanumVoltagesConsumer} instead of {@code 314 * Consumer<MecanumDriveMotorVoltages>}. 315 */ 316 @Deprecated(since = "2025", forRemoval = true) 317 public MecanumControllerCommand( 318 Trajectory trajectory, 319 Supplier<Pose2d> pose, 320 SimpleMotorFeedforward feedforward, 321 MecanumDriveKinematics kinematics, 322 PIDController xController, 323 PIDController yController, 324 ProfiledPIDController thetaController, 325 double maxWheelVelocityMetersPerSecond, 326 PIDController frontLeftController, 327 PIDController rearLeftController, 328 PIDController frontRightController, 329 PIDController rearRightController, 330 Supplier<MecanumDriveWheelSpeeds> currentWheelSpeeds, 331 Consumer<MecanumDriveMotorVoltages> outputDriveVoltages, 332 Subsystem... requirements) { 333 this( 334 trajectory, 335 pose, 336 feedforward, 337 kinematics, 338 xController, 339 yController, 340 thetaController, 341 maxWheelVelocityMetersPerSecond, 342 frontLeftController, 343 rearLeftController, 344 frontRightController, 345 rearRightController, 346 currentWheelSpeeds, 347 (frontLeft, frontRight, rearLeft, rearRight) -> 348 outputDriveVoltages.accept( 349 new MecanumDriveMotorVoltages(frontLeft, frontRight, rearLeft, rearRight)), 350 requirements); 351 } 352 353 /** 354 * Constructs a new MecanumControllerCommand that when executed will follow the provided 355 * trajectory. The user should implement a velocity PID on the desired output wheel velocities. 356 * 357 * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path - 358 * this is left to the user, since it is not appropriate for paths with nonstationary end-states. 359 * 360 * @param trajectory The trajectory to follow. 361 * @param pose A function that supplies the robot pose - use one of the odometry classes to 362 * provide this. 363 * @param kinematics The kinematics for the robot drivetrain. 364 * @param xController The Trajectory Tracker PID controller for the robot's x position. 365 * @param yController The Trajectory Tracker PID controller for the robot's y position. 366 * @param thetaController The Trajectory Tracker PID controller for angle for the robot. 367 * @param desiredRotation The angle that the robot should be facing. This is sampled at each time 368 * step. 369 * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel. 370 * @param outputWheelSpeeds A MecanumDriveWheelSpeeds object containing the output wheel speeds. 371 * @param requirements The subsystems to require. 372 */ 373 @SuppressWarnings("this-escape") 374 public MecanumControllerCommand( 375 Trajectory trajectory, 376 Supplier<Pose2d> pose, 377 MecanumDriveKinematics kinematics, 378 PIDController xController, 379 PIDController yController, 380 ProfiledPIDController thetaController, 381 Supplier<Rotation2d> desiredRotation, 382 double maxWheelVelocityMetersPerSecond, 383 Consumer<MecanumDriveWheelSpeeds> outputWheelSpeeds, 384 Subsystem... requirements) { 385 m_trajectory = requireNonNullParam(trajectory, "trajectory", "MecanumControllerCommand"); 386 m_pose = requireNonNullParam(pose, "pose", "MecanumControllerCommand"); 387 m_feedforward = new SimpleMotorFeedforward(0, 0, 0); 388 m_kinematics = requireNonNullParam(kinematics, "kinematics", "MecanumControllerCommand"); 389 390 m_controller = 391 new HolonomicDriveController( 392 requireNonNullParam(xController, "xController", "MecanumControllerCommand"), 393 requireNonNullParam(yController, "yController", "MecanumControllerCommand"), 394 requireNonNullParam(thetaController, "thetaController", "MecanumControllerCommand")); 395 396 m_desiredRotation = 397 requireNonNullParam(desiredRotation, "desiredRotation", "MecanumControllerCommand"); 398 399 m_maxWheelVelocityMetersPerSecond = maxWheelVelocityMetersPerSecond; 400 401 m_frontLeftController = null; 402 m_rearLeftController = null; 403 m_frontRightController = null; 404 m_rearRightController = null; 405 406 m_currentWheelSpeeds = null; 407 408 m_outputWheelSpeeds = 409 requireNonNullParam(outputWheelSpeeds, "outputWheelSpeeds", "MecanumControllerCommand"); 410 411 m_outputDriveVoltages = null; 412 413 m_usePID = false; 414 415 addRequirements(requirements); 416 } 417 418 /** 419 * Constructs a new MecanumControllerCommand that when executed will follow the provided 420 * trajectory. The user should implement a velocity PID on the desired output wheel velocities. 421 * 422 * <p>Note: The controllers will *not* set the outputVolts to zero upon completion of the path - 423 * this is left to the user, since it is not appropriate for paths with nonstationary end-states. 424 * 425 * <p>Note 2: The final rotation of the robot will be set to the rotation of the final pose in the 426 * trajectory. The robot will not follow the rotations from the poses at each timestep. If 427 * alternate rotation behavior is desired, the other constructor with a supplier for rotation 428 * should be used. 429 * 430 * @param trajectory The trajectory to follow. 431 * @param pose A function that supplies the robot pose - use one of the odometry classes to 432 * provide this. 433 * @param kinematics The kinematics for the robot drivetrain. 434 * @param xController The Trajectory Tracker PID controller for the robot's x position. 435 * @param yController The Trajectory Tracker PID controller for the robot's y position. 436 * @param thetaController The Trajectory Tracker PID controller for angle for the robot. 437 * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel. 438 * @param outputWheelSpeeds A MecanumDriveWheelSpeeds object containing the output wheel speeds. 439 * @param requirements The subsystems to require. 440 */ 441 public MecanumControllerCommand( 442 Trajectory trajectory, 443 Supplier<Pose2d> pose, 444 MecanumDriveKinematics kinematics, 445 PIDController xController, 446 PIDController yController, 447 ProfiledPIDController thetaController, 448 double maxWheelVelocityMetersPerSecond, 449 Consumer<MecanumDriveWheelSpeeds> outputWheelSpeeds, 450 Subsystem... requirements) { 451 this( 452 trajectory, 453 pose, 454 kinematics, 455 xController, 456 yController, 457 thetaController, 458 () -> 459 trajectory.getStates().get(trajectory.getStates().size() - 1).poseMeters.getRotation(), 460 maxWheelVelocityMetersPerSecond, 461 outputWheelSpeeds, 462 requirements); 463 } 464 465 @Override 466 public void initialize() { 467 var initialState = m_trajectory.sample(0); 468 469 var initialXVelocity = 470 initialState.velocityMetersPerSecond * initialState.poseMeters.getRotation().getCos(); 471 var initialYVelocity = 472 initialState.velocityMetersPerSecond * initialState.poseMeters.getRotation().getSin(); 473 474 MecanumDriveWheelSpeeds prevSpeeds = 475 m_kinematics.toWheelSpeeds(new ChassisSpeeds(initialXVelocity, initialYVelocity, 0.0)); 476 477 m_prevFrontLeftSpeedSetpoint = prevSpeeds.frontLeftMetersPerSecond; 478 m_prevRearLeftSpeedSetpoint = prevSpeeds.rearLeftMetersPerSecond; 479 m_prevFrontRightSpeedSetpoint = prevSpeeds.frontRightMetersPerSecond; 480 m_prevRearRightSpeedSetpoint = prevSpeeds.rearRightMetersPerSecond; 481 482 m_timer.restart(); 483 } 484 485 @Override 486 public void execute() { 487 double curTime = m_timer.get(); 488 489 var desiredState = m_trajectory.sample(curTime); 490 491 var targetChassisSpeeds = 492 m_controller.calculate(m_pose.get(), desiredState, m_desiredRotation.get()); 493 var targetWheelSpeeds = m_kinematics.toWheelSpeeds(targetChassisSpeeds); 494 495 targetWheelSpeeds.desaturate(m_maxWheelVelocityMetersPerSecond); 496 497 double frontLeftSpeedSetpoint = targetWheelSpeeds.frontLeftMetersPerSecond; 498 double rearLeftSpeedSetpoint = targetWheelSpeeds.rearLeftMetersPerSecond; 499 double frontRightSpeedSetpoint = targetWheelSpeeds.frontRightMetersPerSecond; 500 double rearRightSpeedSetpoint = targetWheelSpeeds.rearRightMetersPerSecond; 501 502 double frontLeftOutput; 503 double rearLeftOutput; 504 double frontRightOutput; 505 double rearRightOutput; 506 507 if (m_usePID) { 508 final double frontLeftFeedforward = 509 m_feedforward.calculateWithVelocities( 510 m_prevFrontLeftSpeedSetpoint, frontLeftSpeedSetpoint); 511 512 final double rearLeftFeedforward = 513 m_feedforward.calculateWithVelocities(m_prevRearLeftSpeedSetpoint, rearLeftSpeedSetpoint); 514 515 final double frontRightFeedforward = 516 m_feedforward.calculateWithVelocities( 517 m_prevFrontRightSpeedSetpoint, frontRightSpeedSetpoint); 518 519 final double rearRightFeedforward = 520 m_feedforward.calculateWithVelocities( 521 m_prevRearRightSpeedSetpoint, rearRightSpeedSetpoint); 522 523 frontLeftOutput = 524 frontLeftFeedforward 525 + m_frontLeftController.calculate( 526 m_currentWheelSpeeds.get().frontLeftMetersPerSecond, frontLeftSpeedSetpoint); 527 528 rearLeftOutput = 529 rearLeftFeedforward 530 + m_rearLeftController.calculate( 531 m_currentWheelSpeeds.get().rearLeftMetersPerSecond, rearLeftSpeedSetpoint); 532 533 frontRightOutput = 534 frontRightFeedforward 535 + m_frontRightController.calculate( 536 m_currentWheelSpeeds.get().frontRightMetersPerSecond, frontRightSpeedSetpoint); 537 538 rearRightOutput = 539 rearRightFeedforward 540 + m_rearRightController.calculate( 541 m_currentWheelSpeeds.get().rearRightMetersPerSecond, rearRightSpeedSetpoint); 542 543 m_outputDriveVoltages.accept( 544 frontLeftOutput, frontRightOutput, rearLeftOutput, rearRightOutput); 545 546 } else { 547 m_outputWheelSpeeds.accept( 548 new MecanumDriveWheelSpeeds( 549 frontLeftSpeedSetpoint, 550 frontRightSpeedSetpoint, 551 rearLeftSpeedSetpoint, 552 rearRightSpeedSetpoint)); 553 } 554 } 555 556 @Override 557 public void end(boolean interrupted) { 558 m_timer.stop(); 559 } 560 561 @Override 562 public boolean isFinished() { 563 return m_timer.hasElapsed(m_trajectory.getTotalTimeSeconds()); 564 } 565 566 /** A consumer to represent an operation on the voltages of a mecanum drive. */ 567 @FunctionalInterface 568 public interface MecanumVoltagesConsumer { 569 /** 570 * Accepts the voltages to perform some operation with them. 571 * 572 * @param frontLeftVoltage The voltage of the front left motor. 573 * @param frontRightVoltage The voltage of the front right motor. 574 * @param rearLeftVoltage The voltage of the rear left motor. 575 * @param rearRightVoltage The voltage of the rear left motor. 576 */ 577 void accept( 578 double frontLeftVoltage, 579 double frontRightVoltage, 580 double rearLeftVoltage, 581 double rearRightVoltage); 582 } 583}