ChassisSpeeds
- class wpimath.kinematics.ChassisSpeeds(vx: meters_per_second = 0, vy: meters_per_second = 0, omega: radians_per_second = 0)
Bases:
pybind11_object
Represents the speed of a robot chassis. 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, this ChassisSpeeds struct represents a velocity w.r.t to the robot frame of reference.
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.
- static fromFeet(vx: feet_per_second = 0, vy: feet_per_second = 0, omega: radians_per_second = 0) wpimath.kinematics._kinematics.ChassisSpeeds
- static fromFieldRelativeSpeeds(*args, **kwargs)
Overloaded function.
fromFieldRelativeSpeeds(vx: meters_per_second, vy: meters_per_second, omega: radians_per_second, robotAngle: wpimath.geometry._geometry.Rotation2d) -> wpimath.kinematics._kinematics.ChassisSpeeds
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(fieldRelativeSpeeds: wpimath.kinematics._kinematics.ChassisSpeeds, robotAngle: wpimath.geometry._geometry.Rotation2d) -> wpimath.kinematics._kinematics.ChassisSpeeds
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.
- property omega
Represents the angular velocity of the robot frame. (CCW is +)
- property omega_dps
- property vx
Represents forward velocity w.r.t the robot frame of reference. (Fwd is +)
- property vx_fps
- property vy
Represents strafe velocity w.r.t the robot frame of reference. (Left is +)
- property vy_fps