mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] ChassisSpeeds: document that values aren't relative to the robot (NFC) (#5551)
This commit is contained in:
@@ -8,20 +8,19 @@ import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
|
||||
/**
|
||||
* 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.
|
||||
* 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.
|
||||
*
|
||||
* <p>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.
|
||||
*/
|
||||
public class ChassisSpeeds {
|
||||
/** Represents forward velocity w.r.t the robot frame of reference. (Fwd is +) */
|
||||
/** Velocity along the x-axis. (Fwd is +) */
|
||||
public double vxMetersPerSecond;
|
||||
|
||||
/** Represents sideways velocity w.r.t the robot frame of reference. (Left is +) */
|
||||
/** Velocity along the y-axis. (Left is +) */
|
||||
public double vyMetersPerSecond;
|
||||
|
||||
/** Represents the angular velocity of the robot frame. (CCW is +) */
|
||||
|
||||
Reference in New Issue
Block a user