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.math.kinematics; 006 007import static edu.wpi.first.units.Units.MetersPerSecond; 008import static edu.wpi.first.units.Units.RadiansPerSecond; 009import static edu.wpi.first.units.Units.Seconds; 010 011import edu.wpi.first.math.geometry.Pose2d; 012import edu.wpi.first.math.geometry.Rotation2d; 013import edu.wpi.first.math.geometry.Translation2d; 014import edu.wpi.first.math.geometry.Twist2d; 015import edu.wpi.first.math.kinematics.proto.ChassisSpeedsProto; 016import edu.wpi.first.math.kinematics.struct.ChassisSpeedsStruct; 017import edu.wpi.first.units.measure.AngularVelocity; 018import edu.wpi.first.units.measure.LinearVelocity; 019import edu.wpi.first.units.measure.Time; 020import edu.wpi.first.util.protobuf.ProtobufSerializable; 021import edu.wpi.first.util.struct.StructSerializable; 022import java.util.Objects; 023 024/** 025 * Represents the speed of a robot chassis. Although this class contains similar members compared to 026 * a Twist2d, they do NOT represent the same thing. Whereas a Twist2d represents a change in pose 027 * w.r.t to the robot frame of reference, a ChassisSpeeds object represents a robot's velocity. 028 * 029 * <p>A strictly non-holonomic drivetrain, such as a differential drive, should never have a dy 030 * component because it can never move sideways. Holonomic drivetrains such as swerve and mecanum 031 * will often have all three components. 032 */ 033public class ChassisSpeeds implements ProtobufSerializable, StructSerializable { 034 /** Velocity along the x-axis. (Fwd is +) */ 035 public double vxMetersPerSecond; 036 037 /** Velocity along the y-axis. (Left is +) */ 038 public double vyMetersPerSecond; 039 040 /** Represents the angular velocity of the robot frame. (CCW is +) */ 041 public double omegaRadiansPerSecond; 042 043 /** ChassisSpeeds protobuf for serialization. */ 044 public static final ChassisSpeedsProto proto = new ChassisSpeedsProto(); 045 046 /** ChassisSpeeds struct for serialization. */ 047 public static final ChassisSpeedsStruct struct = new ChassisSpeedsStruct(); 048 049 /** Constructs a ChassisSpeeds with zeros for dx, dy, and theta. */ 050 public ChassisSpeeds() {} 051 052 /** 053 * Constructs a ChassisSpeeds object. 054 * 055 * @param vxMetersPerSecond Forward velocity. 056 * @param vyMetersPerSecond Sideways velocity. 057 * @param omegaRadiansPerSecond Angular velocity. 058 */ 059 public ChassisSpeeds( 060 double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond) { 061 this.vxMetersPerSecond = vxMetersPerSecond; 062 this.vyMetersPerSecond = vyMetersPerSecond; 063 this.omegaRadiansPerSecond = omegaRadiansPerSecond; 064 } 065 066 /** 067 * Constructs a ChassisSpeeds object. 068 * 069 * @param vx Forward velocity. 070 * @param vy Sideways velocity. 071 * @param omega Angular velocity. 072 */ 073 public ChassisSpeeds(LinearVelocity vx, LinearVelocity vy, AngularVelocity omega) { 074 this(vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond)); 075 } 076 077 /** 078 * Creates a Twist2d from ChassisSpeeds. 079 * 080 * @param dtSeconds The duration of the timestep. 081 * @return Twist2d. 082 */ 083 public Twist2d toTwist2d(double dtSeconds) { 084 return new Twist2d( 085 vxMetersPerSecond * dtSeconds, 086 vyMetersPerSecond * dtSeconds, 087 omegaRadiansPerSecond * dtSeconds); 088 } 089 090 /** 091 * Discretizes a continuous-time chassis speed. 092 * 093 * <p>This function converts a continuous-time chassis speed into a discrete-time one such that 094 * when the discrete-time chassis speed is applied for one timestep, the robot moves as if the 095 * velocity components are independent (i.e., the robot moves v_x * dt along the x-axis, v_y * dt 096 * along the y-axis, and omega * dt around the z-axis). 097 * 098 * <p>This is useful for compensating for translational skew when translating and rotating a 099 * swerve drivetrain. 100 * 101 * @param vxMetersPerSecond Forward velocity. 102 * @param vyMetersPerSecond Sideways velocity. 103 * @param omegaRadiansPerSecond Angular velocity. 104 * @param dtSeconds The duration of the timestep the speeds should be applied for. 105 * @return Discretized ChassisSpeeds. 106 */ 107 public static ChassisSpeeds discretize( 108 double vxMetersPerSecond, 109 double vyMetersPerSecond, 110 double omegaRadiansPerSecond, 111 double dtSeconds) { 112 // Construct the desired pose after a timestep, relative to the current pose. The desired pose 113 // has decoupled translation and rotation. 114 var desiredDeltaPose = 115 new Pose2d( 116 vxMetersPerSecond * dtSeconds, 117 vyMetersPerSecond * dtSeconds, 118 new Rotation2d(omegaRadiansPerSecond * dtSeconds)); 119 120 // Find the chassis translation/rotation deltas in the robot frame that move the robot from its 121 // current pose to the desired pose 122 var twist = Pose2d.kZero.log(desiredDeltaPose); 123 124 // Turn the chassis translation/rotation deltas into average velocities 125 return new ChassisSpeeds(twist.dx / dtSeconds, twist.dy / dtSeconds, twist.dtheta / dtSeconds); 126 } 127 128 /** 129 * Discretizes a continuous-time chassis speed. 130 * 131 * <p>This function converts a continuous-time chassis speed into a discrete-time one such that 132 * when the discrete-time chassis speed is applied for one timestep, the robot moves as if the 133 * velocity components are independent (i.e., the robot moves v_x * dt along the x-axis, v_y * dt 134 * along the y-axis, and omega * dt around the z-axis). 135 * 136 * <p>This is useful for compensating for translational skew when translating and rotating a 137 * swerve drivetrain. 138 * 139 * @param vx Forward velocity. 140 * @param vy Sideways velocity. 141 * @param omega Angular velocity. 142 * @param dt The duration of the timestep the speeds should be applied for. 143 * @return Discretized ChassisSpeeds. 144 */ 145 public static ChassisSpeeds discretize( 146 LinearVelocity vx, LinearVelocity vy, AngularVelocity omega, Time dt) { 147 return discretize( 148 vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond), dt.in(Seconds)); 149 } 150 151 /** 152 * Discretizes a continuous-time chassis speed. 153 * 154 * <p>This function converts a continuous-time chassis speed into a discrete-time one such that 155 * when the discrete-time chassis speed is applied for one timestep, the robot moves as if the 156 * velocity components are independent (i.e., the robot moves v_x * dt along the x-axis, v_y * dt 157 * along the y-axis, and omega * dt around the z-axis). 158 * 159 * <p>This is useful for compensating for translational skew when translating and rotating a 160 * swerve drivetrain. 161 * 162 * @param continuousSpeeds The continuous speeds. 163 * @param dtSeconds The duration of the timestep the speeds should be applied for. 164 * @return Discretized ChassisSpeeds. 165 */ 166 public static ChassisSpeeds discretize(ChassisSpeeds continuousSpeeds, double dtSeconds) { 167 return discretize( 168 continuousSpeeds.vxMetersPerSecond, 169 continuousSpeeds.vyMetersPerSecond, 170 continuousSpeeds.omegaRadiansPerSecond, 171 dtSeconds); 172 } 173 174 /** 175 * Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds 176 * object. 177 * 178 * @param vxMetersPerSecond The component of speed in the x direction relative to the field. 179 * Positive x is away from your alliance wall. 180 * @param vyMetersPerSecond The component of speed in the y direction relative to the field. 181 * Positive y is to your left when standing behind the alliance wall. 182 * @param omegaRadiansPerSecond The angular rate of the robot. 183 * @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is 184 * considered to be zero when it is facing directly away from your alliance station wall. 185 * Remember that this should be CCW positive. 186 * @return ChassisSpeeds object representing the speeds in the robot's frame of reference. 187 */ 188 public static ChassisSpeeds fromFieldRelativeSpeeds( 189 double vxMetersPerSecond, 190 double vyMetersPerSecond, 191 double omegaRadiansPerSecond, 192 Rotation2d robotAngle) { 193 // CW rotation into chassis frame 194 var rotated = 195 new Translation2d(vxMetersPerSecond, vyMetersPerSecond).rotateBy(robotAngle.unaryMinus()); 196 return new ChassisSpeeds(rotated.getX(), rotated.getY(), omegaRadiansPerSecond); 197 } 198 199 /** 200 * Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds 201 * object. 202 * 203 * @param vx The component of speed in the x direction relative to the field. Positive x is away 204 * from your alliance wall. 205 * @param vy The component of speed in the y direction relative to the field. Positive y is to 206 * your left when standing behind the alliance wall. 207 * @param omega The angular rate of the robot. 208 * @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is 209 * considered to be zero when it is facing directly away from your alliance station wall. 210 * Remember that this should be CCW positive. 211 * @return ChassisSpeeds object representing the speeds in the robot's frame of reference. 212 */ 213 public static ChassisSpeeds fromFieldRelativeSpeeds( 214 LinearVelocity vx, LinearVelocity vy, AngularVelocity omega, Rotation2d robotAngle) { 215 return fromFieldRelativeSpeeds( 216 vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond), robotAngle); 217 } 218 219 /** 220 * Converts a user provided field-relative ChassisSpeeds object into a robot-relative 221 * ChassisSpeeds object. 222 * 223 * @param fieldRelativeSpeeds The ChassisSpeeds object representing the speeds in the field frame 224 * of reference. Positive x is away from your alliance wall. Positive y is to your left when 225 * standing behind the alliance wall. 226 * @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is 227 * considered to be zero when it is facing directly away from your alliance station wall. 228 * Remember that this should be CCW positive. 229 * @return ChassisSpeeds object representing the speeds in the robot's frame of reference. 230 */ 231 public static ChassisSpeeds fromFieldRelativeSpeeds( 232 ChassisSpeeds fieldRelativeSpeeds, Rotation2d robotAngle) { 233 return fromFieldRelativeSpeeds( 234 fieldRelativeSpeeds.vxMetersPerSecond, 235 fieldRelativeSpeeds.vyMetersPerSecond, 236 fieldRelativeSpeeds.omegaRadiansPerSecond, 237 robotAngle); 238 } 239 240 /** 241 * Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds 242 * object. 243 * 244 * @param vxMetersPerSecond The component of speed in the x direction relative to the robot. 245 * Positive x is towards the robot's front. 246 * @param vyMetersPerSecond The component of speed in the y direction relative to the robot. 247 * Positive y is towards the robot's left. 248 * @param omegaRadiansPerSecond The angular rate of the robot. 249 * @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is 250 * considered to be zero when it is facing directly away from your alliance station wall. 251 * Remember that this should be CCW positive. 252 * @return ChassisSpeeds object representing the speeds in the field's frame of reference. 253 */ 254 public static ChassisSpeeds fromRobotRelativeSpeeds( 255 double vxMetersPerSecond, 256 double vyMetersPerSecond, 257 double omegaRadiansPerSecond, 258 Rotation2d robotAngle) { 259 // CCW rotation out of chassis frame 260 var rotated = new Translation2d(vxMetersPerSecond, vyMetersPerSecond).rotateBy(robotAngle); 261 return new ChassisSpeeds(rotated.getX(), rotated.getY(), omegaRadiansPerSecond); 262 } 263 264 /** 265 * Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds 266 * object. 267 * 268 * @param vx The component of speed in the x direction relative to the robot. Positive x is 269 * towards the robot's front. 270 * @param vy The component of speed in the y direction relative to the robot. Positive y is 271 * towards the robot's left. 272 * @param omega The angular rate of the robot. 273 * @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is 274 * considered to be zero when it is facing directly away from your alliance station wall. 275 * Remember that this should be CCW positive. 276 * @return ChassisSpeeds object representing the speeds in the field's frame of reference. 277 */ 278 public static ChassisSpeeds fromRobotRelativeSpeeds( 279 LinearVelocity vx, LinearVelocity vy, AngularVelocity omega, Rotation2d robotAngle) { 280 return fromRobotRelativeSpeeds( 281 vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond), robotAngle); 282 } 283 284 /** 285 * Converts a user provided robot-relative ChassisSpeeds object into a field-relative 286 * ChassisSpeeds object. 287 * 288 * @param robotRelativeSpeeds The ChassisSpeeds object representing the speeds in the robot frame 289 * of reference. Positive x is towards the robot's front. Positive y is towards the robot's 290 * left. 291 * @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is 292 * considered to be zero when it is facing directly away from your alliance station wall. 293 * Remember that this should be CCW positive. 294 * @return ChassisSpeeds object representing the speeds in the field's frame of reference. 295 */ 296 public static ChassisSpeeds fromRobotRelativeSpeeds( 297 ChassisSpeeds robotRelativeSpeeds, Rotation2d robotAngle) { 298 return fromRobotRelativeSpeeds( 299 robotRelativeSpeeds.vxMetersPerSecond, 300 robotRelativeSpeeds.vyMetersPerSecond, 301 robotRelativeSpeeds.omegaRadiansPerSecond, 302 robotAngle); 303 } 304 305 /** 306 * Adds two ChassisSpeeds and returns the sum. 307 * 308 * <p>For example, ChassisSpeeds{1.0, 0.5, 0.75} + ChassisSpeeds{2.0, 1.5, 0.25} = 309 * ChassisSpeeds{3.0, 2.0, 1.0} 310 * 311 * @param other The ChassisSpeeds to add. 312 * @return The sum of the ChassisSpeeds. 313 */ 314 public ChassisSpeeds plus(ChassisSpeeds other) { 315 return new ChassisSpeeds( 316 vxMetersPerSecond + other.vxMetersPerSecond, 317 vyMetersPerSecond + other.vyMetersPerSecond, 318 omegaRadiansPerSecond + other.omegaRadiansPerSecond); 319 } 320 321 /** 322 * Subtracts the other ChassisSpeeds from the current ChassisSpeeds and returns the difference. 323 * 324 * <p>For example, ChassisSpeeds{5.0, 4.0, 2.0} - ChassisSpeeds{1.0, 2.0, 1.0} = 325 * ChassisSpeeds{4.0, 2.0, 1.0} 326 * 327 * @param other The ChassisSpeeds to subtract. 328 * @return The difference between the two ChassisSpeeds. 329 */ 330 public ChassisSpeeds minus(ChassisSpeeds other) { 331 return new ChassisSpeeds( 332 vxMetersPerSecond - other.vxMetersPerSecond, 333 vyMetersPerSecond - other.vyMetersPerSecond, 334 omegaRadiansPerSecond - other.omegaRadiansPerSecond); 335 } 336 337 /** 338 * Returns the inverse of the current ChassisSpeeds. This is equivalent to negating all components 339 * of the ChassisSpeeds. 340 * 341 * @return The inverse of the current ChassisSpeeds. 342 */ 343 public ChassisSpeeds unaryMinus() { 344 return new ChassisSpeeds(-vxMetersPerSecond, -vyMetersPerSecond, -omegaRadiansPerSecond); 345 } 346 347 /** 348 * Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds. 349 * 350 * <p>For example, ChassisSpeeds{2.0, 2.5, 1.0} * 2 = ChassisSpeeds{4.0, 5.0, 1.0} 351 * 352 * @param scalar The scalar to multiply by. 353 * @return The scaled ChassisSpeeds. 354 */ 355 public ChassisSpeeds times(double scalar) { 356 return new ChassisSpeeds( 357 vxMetersPerSecond * scalar, vyMetersPerSecond * scalar, omegaRadiansPerSecond * scalar); 358 } 359 360 /** 361 * Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds. 362 * 363 * <p>For example, ChassisSpeeds{2.0, 2.5, 1.0} / 2 = ChassisSpeeds{1.0, 1.25, 0.5} 364 * 365 * @param scalar The scalar to divide by. 366 * @return The scaled ChassisSpeeds. 367 */ 368 public ChassisSpeeds div(double scalar) { 369 return new ChassisSpeeds( 370 vxMetersPerSecond / scalar, vyMetersPerSecond / scalar, omegaRadiansPerSecond / scalar); 371 } 372 373 @Override 374 public final int hashCode() { 375 return Objects.hash(vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond); 376 } 377 378 @Override 379 public boolean equals(Object o) { 380 return o == this 381 || o instanceof ChassisSpeeds c 382 && vxMetersPerSecond == c.vxMetersPerSecond 383 && vyMetersPerSecond == c.vyMetersPerSecond 384 && omegaRadiansPerSecond == c.omegaRadiansPerSecond; 385 } 386 387 @Override 388 public String toString() { 389 return String.format( 390 "ChassisSpeeds(Vx: %.2f m/s, Vy: %.2f m/s, Omega: %.2f rad/s)", 391 vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond); 392 } 393}