Class ChassisVelocities
- All Implemented Interfaces:
Interpolatable<ChassisVelocities>, ProtobufSerializable, StructSerializable, WPISerializable
Although this class contains similar members compared to a Twist2d, they do NOT represent the same thing. Whereas a Twist2d represents a change in pose w.r.t to the robot frame of reference, a ChassisVelocities object represents a robot's velocities.
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 TypeFieldDescriptiondoubleAngular velocity of the robot frame in radians per second.static final ChassisVelocitiesProtoChassisVelocities protobuf for serialization.static final ChassisVelocitiesStructChassisVelocities struct for serialization.doubleVelocity along the x-axis in meters per second.doubleVelocity along the y-axis in meters per second. -
Constructor Summary
ConstructorsConstructorDescriptionConstructs a ChassisVelocities with zeros for dx, dy, and theta.ChassisVelocities(double vx, double vy, double omega) Constructs a ChassisVelocities object.ChassisVelocities(LinearVelocity vx, LinearVelocity vy, AngularVelocity omega) Constructs a ChassisVelocities object. -
Method Summary
Modifier and TypeMethodDescriptiondiscretize(double dt) Discretizes continuous-time chassis velocities.div(double scalar) Divides the ChassisVelocities by a scalar and returns the new ChassisVelocities.booleanfinal inthashCode()interpolate(ChassisVelocities endValue, double t) Return the interpolated value.minus(ChassisVelocities other) Subtracts the other ChassisVelocities from the current ChassisVelocities and returns the difference.plus(ChassisVelocities other) Adds two ChassisVelocities and returns the sum.times(double scalar) Multiplies the ChassisVelocities by a scalar and returns the new ChassisVelocities.toFieldRelative(Rotation2d robotAngle) Converts this robot-relative set of velocities into a field-relative ChassisVelocities object.toRobotRelative(Rotation2d robotAngle) Converts this field-relative set of velocities into a robot-relative ChassisVelocities object.toString()toTwist2d(double dt) Creates a Twist2d from ChassisVelocities.Returns the inverse of the current ChassisVelocities.
-
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
ChassisVelocities protobuf for serialization. -
struct
ChassisVelocities struct for serialization.
-
-
Constructor Details
-
ChassisVelocities
public ChassisVelocities()Constructs a ChassisVelocities with zeros for dx, dy, and theta. -
ChassisVelocities
Constructs a ChassisVelocities object.- Parameters:
vx- Forward velocity in meters per second.vy- Sideways velocity in meters per second.omega- Angular velocity in radians per second.
-
ChassisVelocities
Constructs a ChassisVelocities object.- Parameters:
vx- Forward velocity.vy- Sideways velocity.omega- Angular velocity.
-
-
Method Details
-
toTwist2d
-
discretize
Discretizes continuous-time chassis velocities.This function converts these continuous-time chassis velocities into discrete-time ones such that when the discrete-time chassis velocities are 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 ChassisVelocities after discretizing (e.g., when desaturating swerve module velocities) 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 velocities should be applied for.- Returns:
- Discretized ChassisVelocities.
-
toRobotRelative
Converts this field-relative set of velocities into a robot-relative ChassisVelocities 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:
- ChassisVelocities object representing the velocities in the robot's frame of reference.
-
toFieldRelative
Converts this robot-relative set of velocities into a field-relative ChassisVelocities 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:
- ChassisVelocities object representing the velocities in the field's frame of reference.
-
plus
Adds two ChassisVelocities and returns the sum.For example, ChassisVelocities{1.0, 0.5, 0.75} + ChassisVelocities{2.0, 1.5, 0.25} = ChassisVelocities{3.0, 2.0, 1.0}
- Parameters:
other- The ChassisVelocities to add.- Returns:
- The sum of the ChassisVelocities.
-
minus
Subtracts the other ChassisVelocities from the current ChassisVelocities and returns the difference.For example, ChassisVelocities{5.0, 4.0, 2.0} - ChassisVelocities{1.0, 2.0, 1.0} = ChassisVelocities{4.0, 2.0, 1.0}
- Parameters:
other- The ChassisVelocities to subtract.- Returns:
- The difference between the two ChassisVelocities.
-
unaryMinus
Returns the inverse of the current ChassisVelocities. This is equivalent to negating all components of the ChassisVelocities.- Returns:
- The inverse of the current ChassisVelocities.
-
times
Multiplies the ChassisVelocities by a scalar and returns the new ChassisVelocities.For example, ChassisVelocities{2.0, 2.5, 1.0} * 2 = ChassisVelocities{4.0, 5.0, 1.0}
- Parameters:
scalar- The scalar to multiply by.- Returns:
- The scaled ChassisVelocities.
-
div
Divides the ChassisVelocities by a scalar and returns the new ChassisVelocities.For example, ChassisVelocities{2.0, 2.5, 1.0} / 2 = ChassisVelocities{1.0, 1.25, 0.5}
- Parameters:
scalar- The scalar to divide by.- Returns:
- The scaled ChassisVelocities.
-
interpolate
Description copied from interface:InterpolatableReturn the interpolated value. This object is assumed to be the starting position, or lower bound.- Specified by:
interpolatein interfaceInterpolatable<ChassisVelocities>- Parameters:
endValue- The upper bound, or end.t- How far between the lower and upper bound we are. This should be bounded in [0, 1].- Returns:
- The interpolated value.
-
hashCode
-
equals
-
toString
-