Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.math.kinematics.ChassisSpeeds Class Reference
Inheritance diagram for edu.wpi.first.math.kinematics.ChassisSpeeds:
edu.wpi.first.util.protobuf.ProtobufSerializable edu.wpi.first.util.struct.StructSerializable edu.wpi.first.util.WPISerializable edu.wpi.first.util.WPISerializable

Public Member Functions

 ChassisSpeeds ()
 
 ChassisSpeeds (double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond)
 
 ChassisSpeeds (Measure< Velocity< Distance > > vx, Measure< Velocity< Distance > > vy, Measure< Velocity< Angle > > omega)
 
ChassisSpeeds plus (ChassisSpeeds other)
 
ChassisSpeeds minus (ChassisSpeeds other)
 
ChassisSpeeds unaryMinus ()
 
ChassisSpeeds times (double scalar)
 
ChassisSpeeds div (double scalar)
 

Static Public Member Functions

static ChassisSpeeds discretize (double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, double dtSeconds)
 
static ChassisSpeeds discretize (Measure< Velocity< Distance > > vx, Measure< Velocity< Distance > > vy, Measure< Velocity< Angle > > omega, Measure< Time > dt)
 
static ChassisSpeeds discretize (ChassisSpeeds continuousSpeeds, double dtSeconds)
 
static ChassisSpeeds fromFieldRelativeSpeeds (double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, Rotation2d robotAngle)
 
static ChassisSpeeds fromFieldRelativeSpeeds (Measure< Velocity< Distance > > vx, Measure< Velocity< Distance > > vy, Measure< Velocity< Angle > > omega, Rotation2d robotAngle)
 
static ChassisSpeeds fromFieldRelativeSpeeds (ChassisSpeeds fieldRelativeSpeeds, Rotation2d robotAngle)
 
static ChassisSpeeds fromRobotRelativeSpeeds (double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond, Rotation2d robotAngle)
 
static ChassisSpeeds fromRobotRelativeSpeeds (Measure< Velocity< Distance > > vx, Measure< Velocity< Distance > > vy, Measure< Velocity< Angle > > omega, Rotation2d robotAngle)
 
static ChassisSpeeds fromRobotRelativeSpeeds (ChassisSpeeds robotRelativeSpeeds, Rotation2d robotAngle)
 

Public Attributes

double vxMetersPerSecond
 
double vyMetersPerSecond
 
double omegaRadiansPerSecond
 

Static Public Attributes

static final ChassisSpeedsProto proto = new ChassisSpeedsProto()
 
static final ChassisSpeedsStruct struct = new ChassisSpeedsStruct()
 

Detailed Description

Represents the speed of a robot chassis. 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 ChassisSpeeds object represents a robot's velocity.

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.

Constructor & Destructor Documentation

◆ ChassisSpeeds() [1/3]

edu.wpi.first.math.kinematics.ChassisSpeeds.ChassisSpeeds ( )

Constructs a ChassisSpeeds with zeros for dx, dy, and theta.

◆ ChassisSpeeds() [2/3]

edu.wpi.first.math.kinematics.ChassisSpeeds.ChassisSpeeds ( double vxMetersPerSecond,
double vyMetersPerSecond,
double omegaRadiansPerSecond )

Constructs a ChassisSpeeds object.

Parameters
vxMetersPerSecondForward velocity.
vyMetersPerSecondSideways velocity.
omegaRadiansPerSecondAngular velocity.

◆ ChassisSpeeds() [3/3]

edu.wpi.first.math.kinematics.ChassisSpeeds.ChassisSpeeds ( Measure< Velocity< Distance > > vx,
Measure< Velocity< Distance > > vy,
Measure< Velocity< Angle > > omega )

Constructs a ChassisSpeeds object.

Parameters
vxForward velocity.
vySideways velocity.
omegaAngular velocity.

Member Function Documentation

◆ discretize() [1/3]

static ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.discretize ( ChassisSpeeds continuousSpeeds,
double dtSeconds )
static

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
continuousSpeedsThe continuous speeds.
dtSecondsThe duration of the timestep the speeds should be applied for.
Returns
Discretized ChassisSpeeds.

◆ discretize() [2/3]

static ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.discretize ( double vxMetersPerSecond,
double vyMetersPerSecond,
double omegaRadiansPerSecond,
double dtSeconds )
static

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
vxMetersPerSecondForward velocity.
vyMetersPerSecondSideways velocity.
omegaRadiansPerSecondAngular velocity.
dtSecondsThe duration of the timestep the speeds should be applied for.
Returns
Discretized ChassisSpeeds.

◆ discretize() [3/3]

static ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.discretize ( Measure< Velocity< Distance > > vx,
Measure< Velocity< Distance > > vy,
Measure< Velocity< Angle > > omega,
Measure< Time > dt )
static

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
vxForward velocity.
vySideways velocity.
omegaAngular velocity.
dtThe duration of the timestep the speeds should be applied for.
Returns
Discretized ChassisSpeeds.

◆ div()

ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.div ( double scalar)

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
scalarThe scalar to divide by.
Returns
The scaled ChassisSpeeds.

◆ fromFieldRelativeSpeeds() [1/3]

static ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.fromFieldRelativeSpeeds ( ChassisSpeeds fieldRelativeSpeeds,
Rotation2d robotAngle )
static

Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds object.

Parameters
fieldRelativeSpeedsThe 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.
robotAngleThe 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() [2/3]

static ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.fromFieldRelativeSpeeds ( double vxMetersPerSecond,
double vyMetersPerSecond,
double omegaRadiansPerSecond,
Rotation2d robotAngle )
static

Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.

Parameters
vxMetersPerSecondThe component of speed in the x direction relative to the field. Positive x is away from your alliance wall.
vyMetersPerSecondThe component of speed in the y direction relative to the field. Positive y is to your left when standing behind the alliance wall.
omegaRadiansPerSecondThe angular rate of the robot.
robotAngleThe 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() [3/3]

static ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.fromFieldRelativeSpeeds ( Measure< Velocity< Distance > > vx,
Measure< Velocity< Distance > > vy,
Measure< Velocity< Angle > > omega,
Rotation2d robotAngle )
static

Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.

Parameters
vxThe component of speed in the x direction relative to the field. Positive x is away from your alliance wall.
vyThe component of speed in the y direction relative to the field. Positive y is to your left when standing behind the alliance wall.
omegaThe angular rate of the robot.
robotAngleThe 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() [1/3]

static ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.fromRobotRelativeSpeeds ( ChassisSpeeds robotRelativeSpeeds,
Rotation2d robotAngle )
static

Converts a user provided robot-relative ChassisSpeeds object into a field-relative ChassisSpeeds object.

Parameters
robotRelativeSpeedsThe 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.
robotAngleThe 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() [2/3]

static ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.fromRobotRelativeSpeeds ( double vxMetersPerSecond,
double vyMetersPerSecond,
double omegaRadiansPerSecond,
Rotation2d robotAngle )
static

Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object.

Parameters
vxMetersPerSecondThe component of speed in the x direction relative to the robot. Positive x is towards the robot's front.
vyMetersPerSecondThe component of speed in the y direction relative to the robot. Positive y is towards the robot's left.
omegaRadiansPerSecondThe angular rate of the robot.
robotAngleThe 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() [3/3]

static ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.fromRobotRelativeSpeeds ( Measure< Velocity< Distance > > vx,
Measure< Velocity< Distance > > vy,
Measure< Velocity< Angle > > omega,
Rotation2d robotAngle )
static

Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object.

Parameters
vxThe component of speed in the x direction relative to the robot. Positive x is towards the robot's front.
vyThe component of speed in the y direction relative to the robot. Positive y is towards the robot's left.
omegaThe angular rate of the robot.
robotAngleThe 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.

◆ minus()

ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.minus ( ChassisSpeeds other)

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
otherThe ChassisSpeeds to subtract.
Returns
The difference between the two ChassisSpeeds.

◆ plus()

ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.plus ( ChassisSpeeds other)

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
otherThe ChassisSpeeds to add.
Returns
The sum of the ChassisSpeeds.

◆ times()

ChassisSpeeds edu.wpi.first.math.kinematics.ChassisSpeeds.times ( double scalar)

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
scalarThe scalar to multiply by.
Returns
The scaled ChassisSpeeds.

◆ unaryMinus()

ChassisSpeeds edu.wpi.first.math.kinematics.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.

Member Data Documentation

◆ omegaRadiansPerSecond

double edu.wpi.first.math.kinematics.ChassisSpeeds.omegaRadiansPerSecond

Represents the angular velocity of the robot frame. (CCW is +)

◆ proto

final ChassisSpeedsProto edu.wpi.first.math.kinematics.ChassisSpeeds.proto = new ChassisSpeedsProto()
static

ChassisSpeeds protobuf for serialization.

◆ struct

final ChassisSpeedsStruct edu.wpi.first.math.kinematics.ChassisSpeeds.struct = new ChassisSpeedsStruct()
static

ChassisSpeeds struct for serialization.

◆ vxMetersPerSecond

double edu.wpi.first.math.kinematics.ChassisSpeeds.vxMetersPerSecond

Velocity along the x-axis. (Fwd is +)

◆ vyMetersPerSecond

double edu.wpi.first.math.kinematics.ChassisSpeeds.vyMetersPerSecond

Velocity along the y-axis. (Left is +)


The documentation for this class was generated from the following file: