Skip to content

Commit

Permalink
[wpimath] ChassisSpeeds: document that values aren't relative to the …
Browse files Browse the repository at this point in the history
…robot (NFC) (wpilibsuite#5551)
  • Loading branch information
Gold856 authored Aug 30, 2023
1 parent 3c04580 commit 4e0d785
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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.
*
* <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 +) */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,21 +16,20 @@ 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
* drivetrains such as swerve and mecanum will often have all three components.
*/
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;

Expand Down

0 comments on commit 4e0d785

Please sign in to comment.