diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java index 5018d1d7d82..c0370cea0b5 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java @@ -8,20 +8,19 @@ 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. * *
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 +) */ diff --git a/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h b/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h index ab6dd1d042b..b388d5cec85 100644 --- a/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h +++ b/wpimath/src/main/native/include/frc/kinematics/ChassisSpeeds.h @@ -16,8 +16,7 @@ namespace frc { * 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. + * reference, a ChassisSpeeds struct 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 @@ -25,12 +24,12 @@ namespace frc { */ struct WPILIB_DLLEXPORT ChassisSpeeds { /** - * Represents forward velocity w.r.t the robot frame of reference. (Fwd is +) + * Velocity along the x-axis. (Fwd is +) */ units::meters_per_second_t vx = 0_mps; /** - * Represents strafe velocity w.r.t the robot frame of reference. (Left is +) + * Velocity along the y-axis. (Left is +) */ units::meters_per_second_t vy = 0_mps;