Class ChassisSpeeds
- All Implemented Interfaces:
ProtobufSerializable
,StructSerializable
,WPISerializable
public class ChassisSpeeds extends Object implements ProtobufSerializable, StructSerializable
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
Fields Modifier and Type Field Description double
omegaRadiansPerSecond
Represents the angular velocity of the robot frame.static ChassisSpeedsProto
proto
ChassisSpeeds protobuf for serialization.static ChassisSpeedsStruct
struct
ChassisSpeeds struct for serialization.double
vxMetersPerSecond
Velocity along the x-axis.double
vyMetersPerSecond
Velocity along the y-axis. -
Constructor Summary
Constructors Constructor Description ChassisSpeeds()
Constructs a ChassisSpeeds with zeros for dx, dy, and theta.ChassisSpeeds(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond)
Constructs a ChassisSpeeds object.ChassisSpeeds(Measure<Velocity<Distance>> vx, Measure<Velocity<Distance>> vy, Measure<Velocity<Angle>> omega)
Constructs a ChassisSpeeds object. -
Method Summary
Modifier and Type Method Description static ChassisSpeeds
discretize(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, double dtSeconds)
Discretizes a continuous-time chassis speed.static ChassisSpeeds
discretize(ChassisSpeeds continuousSpeeds, double dtSeconds)
Discretizes a continuous-time chassis speed.static ChassisSpeeds
discretize(Measure<Velocity<Distance>> vx, Measure<Velocity<Distance>> vy, Measure<Velocity<Angle>> omega, Measure<Time> dt)
Discretizes a continuous-time chassis speed.ChassisSpeeds
div(double scalar)
Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.static ChassisSpeeds
fromFieldRelativeSpeeds(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, Rotation2d robotAngle)
Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.static ChassisSpeeds
fromFieldRelativeSpeeds(ChassisSpeeds fieldRelativeSpeeds, Rotation2d robotAngle)
Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds object.static ChassisSpeeds
fromFieldRelativeSpeeds(Measure<Velocity<Distance>> vx, Measure<Velocity<Distance>> vy, Measure<Velocity<Angle>> omega, Rotation2d robotAngle)
Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.static ChassisSpeeds
fromRobotRelativeSpeeds(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, Rotation2d robotAngle)
Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object.static ChassisSpeeds
fromRobotRelativeSpeeds(ChassisSpeeds robotRelativeSpeeds, Rotation2d robotAngle)
Converts a user provided robot-relative ChassisSpeeds object into a field-relative ChassisSpeeds object.static ChassisSpeeds
fromRobotRelativeSpeeds(Measure<Velocity<Distance>> vx, Measure<Velocity<Distance>> vy, Measure<Velocity<Angle>> omega, Rotation2d robotAngle)
Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object.ChassisSpeeds
minus(ChassisSpeeds other)
Subtracts the other ChassisSpeeds from the current ChassisSpeeds and returns the difference.ChassisSpeeds
plus(ChassisSpeeds other)
Adds two ChassisSpeeds and returns the sum.ChassisSpeeds
times(double scalar)
Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.String
toString()
ChassisSpeeds
unaryMinus()
Returns the inverse of the current ChassisSpeeds.
-
Field Details
-
vxMetersPerSecond
Velocity along the x-axis. (Fwd is +) -
vyMetersPerSecond
Velocity along the y-axis. (Left is +) -
omegaRadiansPerSecond
Represents the angular velocity of the robot frame. (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
public ChassisSpeeds(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond)Constructs a ChassisSpeeds object.- Parameters:
vxMetersPerSecond
- Forward velocity.vyMetersPerSecond
- Sideways velocity.omegaRadiansPerSecond
- Angular velocity.
-
ChassisSpeeds
public ChassisSpeeds(Measure<Velocity<Distance>> vx, Measure<Velocity<Distance>> vy, Measure<Velocity<Angle>> omega)Constructs a ChassisSpeeds object.- Parameters:
vx
- Forward velocity.vy
- Sideways velocity.omega
- Angular velocity.
-
-
Method Details
-
discretize
public static ChassisSpeeds discretize(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, double dtSeconds)Discretizes a continuous-time chassis speed.This function converts a 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 swerve drivetrain.
- Parameters:
vxMetersPerSecond
- Forward velocity.vyMetersPerSecond
- Sideways velocity.omegaRadiansPerSecond
- Angular velocity.dtSeconds
- The duration of the timestep the speeds should be applied for.- Returns:
- Discretized ChassisSpeeds.
-
discretize
public static ChassisSpeeds discretize(Measure<Velocity<Distance>> vx, Measure<Velocity<Distance>> vy, Measure<Velocity<Angle>> omega, Measure<Time> dt)Discretizes a continuous-time chassis speed.This function converts a 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 swerve drivetrain.
- Parameters:
vx
- Forward velocity.vy
- Sideways velocity.omega
- Angular velocity.dt
- The duration of the timestep the speeds should be applied for.- Returns:
- Discretized ChassisSpeeds.
-
discretize
Discretizes a continuous-time chassis speed.This function converts a continous-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 swerve drivetrain.
- Parameters:
continuousSpeeds
- The continuous speeds.dtSeconds
- The duration of the timestep the speeds should be applied for.- Returns:
- Discretized ChassisSpeeds.
-
fromFieldRelativeSpeeds
public static ChassisSpeeds fromFieldRelativeSpeeds(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, Rotation2d robotAngle)Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.- Parameters:
vxMetersPerSecond
- The component of speed in the x direction relative to the field. Positive x is away from your alliance wall.vyMetersPerSecond
- The component of speed in the y direction relative to the field. Positive y is to your left when standing behind the alliance wall.omegaRadiansPerSecond
- The angular rate of the robot.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.
-
fromFieldRelativeSpeeds
public static ChassisSpeeds fromFieldRelativeSpeeds(Measure<Velocity<Distance>> vx, Measure<Velocity<Distance>> vy, Measure<Velocity<Angle>> omega, Rotation2d robotAngle)Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.- Parameters:
vx
- The component of speed in the x direction relative to the field. Positive x is away from your alliance wall.vy
- The component of speed in the y direction relative to the field. Positive y is to your left when standing behind the alliance wall.omega
- The angular rate of the robot.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.
-
fromFieldRelativeSpeeds
public static ChassisSpeeds fromFieldRelativeSpeeds(ChassisSpeeds fieldRelativeSpeeds, Rotation2d robotAngle)Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds object.- Parameters:
fieldRelativeSpeeds
- The ChassisSpeeds object representing the speeds in the field frame of reference. Positive x is away from your alliance wall. Positive y is to your left when standing behind the alliance wall.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.
-
fromRobotRelativeSpeeds
public static ChassisSpeeds fromRobotRelativeSpeeds(double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, Rotation2d robotAngle)Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object.- Parameters:
vxMetersPerSecond
- The component of speed in the x direction relative to the robot. Positive x is towards the robot's front.vyMetersPerSecond
- The component of speed in the y direction relative to the robot. Positive y is towards the robot's left.omegaRadiansPerSecond
- The angular rate of the robot.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.
-
fromRobotRelativeSpeeds
public static ChassisSpeeds fromRobotRelativeSpeeds(Measure<Velocity<Distance>> vx, Measure<Velocity<Distance>> vy, Measure<Velocity<Angle>> omega, Rotation2d robotAngle)Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object.- Parameters:
vx
- The component of speed in the x direction relative to the robot. Positive x is towards the robot's front.vy
- The component of speed in the y direction relative to the robot. Positive y is towards the robot's left.omega
- The angular rate of the robot.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.
-
fromRobotRelativeSpeeds
public static ChassisSpeeds fromRobotRelativeSpeeds(ChassisSpeeds robotRelativeSpeeds, Rotation2d robotAngle)Converts a user provided robot-relative ChassisSpeeds object into a field-relative ChassisSpeeds object.- Parameters:
robotRelativeSpeeds
- The ChassisSpeeds object representing the speeds in the robot frame of reference. Positive x is towards the robot's front. Positive y is towards the robot's left.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.
-
toString
-