7#include "wpi/units/acceleration.hpp"
18 units::meters_per_second_squared_t
left = 0_mps_sq;
23 units::meters_per_second_squared_t
right = 0_mps_sq;
55 return *
this + -other;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Definition LinearSystem.hpp:20
Represents the wheel accelerations for a differential drive drivetrain.
Definition DifferentialDriveWheelAccelerations.hpp:14
constexpr DifferentialDriveWheelAccelerations operator*(double scalar) const
Multiplies the DifferentialDriveWheelAccelerations by a scalar and returns the new DifferentialDriveW...
Definition DifferentialDriveWheelAccelerations.hpp:80
units::meters_per_second_squared_t left
Acceleration of the left side of the robot.
Definition DifferentialDriveWheelAccelerations.hpp:18
constexpr bool operator==(const DifferentialDriveWheelAccelerations &other) const =default
Compares two DifferentialDriveWheelAccelerations objects.
constexpr DifferentialDriveWheelAccelerations operator-(const DifferentialDriveWheelAccelerations &other) const
Subtracts the other DifferentialDriveWheelAccelerations from the current DifferentialDriveWheelAccele...
Definition DifferentialDriveWheelAccelerations.hpp:53
constexpr DifferentialDriveWheelAccelerations operator/(double scalar) const
Divides the DifferentialDriveWheelAccelerations by a scalar and returns the new DifferentialDriveWhee...
Definition DifferentialDriveWheelAccelerations.hpp:95
constexpr DifferentialDriveWheelAccelerations operator-() const
Returns the inverse of the current DifferentialDriveWheelAccelerations.
Definition DifferentialDriveWheelAccelerations.hpp:65
constexpr DifferentialDriveWheelAccelerations operator+(const DifferentialDriveWheelAccelerations &other) const
Adds two DifferentialDriveWheelAccelerations and returns the sum.
Definition DifferentialDriveWheelAccelerations.hpp:36
units::meters_per_second_squared_t right
Acceleration of the right side of the robot.
Definition DifferentialDriveWheelAccelerations.hpp:23