Class ChassisSpeeds
- All Implemented Interfaces:
ProtobufSerializable
,StructSerializable
,WPISerializable
A strictly non-holonomic drivetrain, such as a differential drive, should never have a dy component because it can never move sideways. Holonomic drivetrains such as swerve and mecanum will often have all three components.
-
Field Summary
FieldsModifier and TypeFieldDescriptiondouble
Angular velocity of the robot frame in radians per second.static final ChassisSpeedsProto
ChassisSpeeds protobuf for serialization.static final ChassisSpeedsStruct
ChassisSpeeds struct for serialization.double
Velocity along the x-axis in meters per second.double
Velocity along the y-axis in meters per second. -
Constructor Summary
ConstructorsConstructorDescriptionConstructs a ChassisSpeeds with zeros for dx, dy, and theta.ChassisSpeeds
(double vx, double vy, double omega) Constructs a ChassisSpeeds object.ChassisSpeeds
(LinearVelocity vx, LinearVelocity vy, AngularVelocity omega) Constructs a ChassisSpeeds object. -
Method Summary
Modifier and TypeMethodDescriptiondiscretize
(double dt) Discretizes a continuous-time chassis speed.div
(double scalar) Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.boolean
final int
hashCode()
minus
(ChassisSpeeds other) Subtracts the other ChassisSpeeds from the current ChassisSpeeds and returns the difference.plus
(ChassisSpeeds other) Adds two ChassisSpeeds and returns the sum.times
(double scalar) Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.toFieldRelative
(Rotation2d robotAngle) Converts this robot-relative set of speeds into a field-relative ChassisSpeeds object.toRobotRelative
(Rotation2d robotAngle) Converts this field-relative set of speeds into a robot-relative ChassisSpeeds object.toString()
toTwist2d
(double dt) Creates a Twist2d from ChassisSpeeds.Returns the inverse of the current ChassisSpeeds.
-
Field Details
-
vx
Velocity along the x-axis in meters per second. (Fwd is +) -
vy
Velocity along the y-axis in meters per second. (Left is +) -
omega
Angular velocity of the robot frame in radians per second. (CCW is +) -
proto
ChassisSpeeds protobuf for serialization. -
struct
ChassisSpeeds struct for serialization.
-
-
Constructor Details
-
ChassisSpeeds
public ChassisSpeeds()Constructs a ChassisSpeeds with zeros for dx, dy, and theta. -
ChassisSpeeds
Constructs a ChassisSpeeds object.- Parameters:
vx
- Forward velocity in meters per second.vy
- Sideways velocity in meters per second.omega
- Angular velocity in radians per second.
-
ChassisSpeeds
Constructs a ChassisSpeeds object.- Parameters:
vx
- Forward velocity.vy
- Sideways velocity.omega
- Angular velocity.
-
-
Method Details
-
toTwist2d
Creates a Twist2d from ChassisSpeeds.- Parameters:
dt
- The duration of the timestep in seconds.- Returns:
- Twist2d.
-
discretize
Discretizes a continuous-time chassis speed.This function converts this continuous-time chassis speed into a discrete-time one such that when the discrete-time chassis speed is applied for one timestep, the robot moves as if the velocity components are independent (i.e., the robot moves v_x * dt along the x-axis, v_y * dt along the y-axis, and omega * dt around the z-axis).
This is useful for compensating for translational skew when translating and rotating a holonomic (swerve or mecanum) drivetrain. However, scaling down the ChassisSpeeds after discretizing (e.g., when desaturating swerve module speeds) rotates the direction of net motion in the opposite direction of rotational velocity, introducing a different translational skew which is not accounted for by discretization.
- Parameters:
dt
- The duration of the timestep in seconds the speeds should be applied for.- Returns:
- Discretized ChassisSpeeds.
-
toRobotRelative
Converts this field-relative set of speeds into a robot-relative ChassisSpeeds object.- Parameters:
robotAngle
- The angle of the robot as measured by a gyroscope. The robot's angle is considered to be zero when it is facing directly away from your alliance station wall. Remember that this should be CCW positive.- Returns:
- ChassisSpeeds object representing the speeds in the robot's frame of reference.
-
toFieldRelative
Converts this robot-relative set of speeds into a field-relative ChassisSpeeds object.- Parameters:
robotAngle
- The angle of the robot as measured by a gyroscope. The robot's angle is considered to be zero when it is facing directly away from your alliance station wall. Remember that this should be CCW positive.- Returns:
- ChassisSpeeds object representing the speeds in the field's frame of reference.
-
plus
Adds two ChassisSpeeds and returns the sum.For example, ChassisSpeeds{1.0, 0.5, 0.75} + ChassisSpeeds{2.0, 1.5, 0.25} = ChassisSpeeds{3.0, 2.0, 1.0}
- Parameters:
other
- The ChassisSpeeds to add.- Returns:
- The sum of the ChassisSpeeds.
-
minus
Subtracts the other ChassisSpeeds from the current ChassisSpeeds and returns the difference.For example, ChassisSpeeds{5.0, 4.0, 2.0} - ChassisSpeeds{1.0, 2.0, 1.0} = ChassisSpeeds{4.0, 2.0, 1.0}
- Parameters:
other
- The ChassisSpeeds to subtract.- Returns:
- The difference between the two ChassisSpeeds.
-
unaryMinus
Returns the inverse of the current ChassisSpeeds. This is equivalent to negating all components of the ChassisSpeeds.- Returns:
- The inverse of the current ChassisSpeeds.
-
times
Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.For example, ChassisSpeeds{2.0, 2.5, 1.0} * 2 = ChassisSpeeds{4.0, 5.0, 1.0}
- Parameters:
scalar
- The scalar to multiply by.- Returns:
- The scaled ChassisSpeeds.
-
div
Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.For example, ChassisSpeeds{2.0, 2.5, 1.0} / 2 = ChassisSpeeds{1.0, 1.25, 0.5}
- Parameters:
scalar
- The scalar to divide by.- Returns:
- The scaled ChassisSpeeds.
-
hashCode
-
equals
-
toString
-