WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
DifferentialDriveWheelAccelerations.hpp
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include "wpi/units/acceleration.hpp"
9
10namespace wpi::math {
11/**
12 * Represents the wheel accelerations for a differential drive drivetrain.
13 */
15 /**
16 * Acceleration of the left side of the robot.
17 */
18 units::meters_per_second_squared_t left = 0_mps_sq;
19
20 /**
21 * Acceleration of the right side of the robot.
22 */
23 units::meters_per_second_squared_t right = 0_mps_sq;
24
25 /**
26 * Adds two DifferentialDriveWheelAccelerations and returns the sum.
27 *
28 * For example, DifferentialDriveWheelAccelerations{1.0, 0.5} +
29 * DifferentialDriveWheelAccelerations{2.0, 1.5} =
30 * DifferentialDriveWheelAccelerations{3.0, 2.0}
31 *
32 * @param other The DifferentialDriveWheelAccelerations to add.
33 *
34 * @return The sum of the DifferentialDriveWheelAccelerations.
35 */
37 const DifferentialDriveWheelAccelerations& other) const {
38 return {left + other.left, right + other.right};
39 }
40
41 /**
42 * Subtracts the other DifferentialDriveWheelAccelerations from the current
43 * DifferentialDriveWheelAccelerations and returns the difference.
44 *
45 * For example, DifferentialDriveWheelAccelerations{5.0, 4.0} -
46 * DifferentialDriveWheelAccelerations{1.0, 2.0} =
47 * DifferentialDriveWheelAccelerations{4.0, 2.0}
48 *
49 * @param other The DifferentialDriveWheelAccelerations to subtract.
50 *
51 * @return The difference between the two DifferentialDriveWheelAccelerations.
52 */
54 const DifferentialDriveWheelAccelerations& other) const {
55 return *this + -other;
56 }
57
58 /**
59 * Returns the inverse of the current DifferentialDriveWheelAccelerations.
60 * This is equivalent to negating all components of the
61 * DifferentialDriveWheelAccelerations.
62 *
63 * @return The inverse of the current DifferentialDriveWheelAccelerations.
64 */
66 return {-left, -right};
67 }
68
69 /**
70 * Multiplies the DifferentialDriveWheelAccelerations by a scalar and returns
71 * the new DifferentialDriveWheelAccelerations.
72 *
73 * For example, DifferentialDriveWheelAccelerations{2.0, 2.5} * 2
74 * = DifferentialDriveWheelAccelerations{4.0, 5.0}
75 *
76 * @param scalar The scalar to multiply by.
77 *
78 * @return The scaled DifferentialDriveWheelAccelerations.
79 */
80 constexpr DifferentialDriveWheelAccelerations operator*(double scalar) const {
81 return {scalar * left, scalar * right};
82 }
83
84 /**
85 * Divides the DifferentialDriveWheelAccelerations by a scalar and returns the
86 * new DifferentialDriveWheelAccelerations.
87 *
88 * For example, DifferentialDriveWheelAccelerations{2.0, 2.5} / 2
89 * = DifferentialDriveWheelAccelerations{1.0, 1.25}
90 *
91 * @param scalar The scalar to divide by.
92 *
93 * @return The scaled DifferentialDriveWheelAccelerations.
94 */
95 constexpr DifferentialDriveWheelAccelerations operator/(double scalar) const {
96 return operator*(1.0 / scalar);
97 }
98
99 /**
100 * Compares two DifferentialDriveWheelAccelerations objects.
101 *
102 * @param other The other DifferentialDriveWheelAccelerations.
103 *
104 * @return True if the DifferentialDriveWheelAccelerations are equal.
105 */
106 constexpr bool operator==(
107 const DifferentialDriveWheelAccelerations& other) const = default;
108};
109} // namespace wpi::math
110
#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