ChassisVelocities
- class wpimath.ChassisVelocities(vx: wpimath.units.meters_per_second = 0, vy: wpimath.units.meters_per_second = 0, omega: wpimath.units.radians_per_second = 0)
Bases:
pybind11_objectRepresents robot chassis velocities.
Although this struct 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 struct 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.
- WPIStruct = <capsule object "WPyStruct">
- discretize(dt: wpimath.units.seconds) wpimath._wpimath.ChassisVelocities
Discretizes continuous-time chassis velocities.
This function converts 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 the velocities should be applied for.
- Returns:
Discretized ChassisVelocities.
- static fromFeet(vx: wpimath.units.feet_per_second = 0, vy: wpimath.units.feet_per_second = 0, omega: wpimath.units.radians_per_second = 0) wpimath._wpimath.ChassisVelocities
- property omega_dps
- toFieldRelative(robotAngle: wpimath._wpimath.Rotation2d) wpimath._wpimath.ChassisVelocities
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.
- toRobotRelative(robotAngle: wpimath._wpimath.Rotation2d) wpimath._wpimath.ChassisVelocities
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.
- toTwist2d(dt: wpimath.units.seconds) wpimath._wpimath.Twist2d
Creates a Twist2d from ChassisVelocities.
- Parameters:
dt – The duration of the timestep.
- Returns:
Twist2d.
- property vx_fps
- property vy_fps