WPILibC++ 2024.3.2
DifferentialDriveWheelSpeeds.h
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/SymbolExports.h>
8
9#include "units/velocity.h"
10
11namespace frc {
12/**
13 * Represents the wheel speeds for a differential drive drivetrain.
14 */
16 /**
17 * Speed of the left side of the robot.
18 */
19 units::meters_per_second_t left = 0_mps;
20
21 /**
22 * Speed of the right side of the robot.
23 */
24 units::meters_per_second_t right = 0_mps;
25
26 /**
27 * Renormalizes the wheel speeds if either side is above the specified
28 * maximum.
29 *
30 * Sometimes, after inverse kinematics, the requested speed from one or more
31 * wheels may be above the max attainable speed for the driving motor on that
32 * wheel. To fix this issue, one can reduce all the wheel speeds to make sure
33 * that all requested module speeds are at-or-below the absolute threshold,
34 * while maintaining the ratio of speeds between wheels.
35 *
36 * @param attainableMaxSpeed The absolute max speed that a wheel can reach.
37 */
38 void Desaturate(units::meters_per_second_t attainableMaxSpeed);
39
40 /**
41 * Adds two DifferentialDriveWheelSpeeds and returns the sum.
42 *
43 * <p>For example, DifferentialDriveWheelSpeeds{1.0, 0.5} +
44 * DifferentialDriveWheelSpeeds{2.0, 1.5} =
45 * DifferentialDriveWheelSpeeds{3.0, 2.0}
46 *
47 * @param other The DifferentialDriveWheelSpeeds to add.
48 *
49 * @return The sum of the DifferentialDriveWheelSpeeds.
50 */
52 const DifferentialDriveWheelSpeeds& other) const {
53 return {left + other.left, right + other.right};
54 }
55
56 /**
57 * Subtracts the other DifferentialDriveWheelSpeeds from the current
58 * DifferentialDriveWheelSpeeds and returns the difference.
59 *
60 * <p>For example, DifferentialDriveWheelSpeeds{5.0, 4.0} -
61 * DifferentialDriveWheelSpeeds{1.0, 2.0} =
62 * DifferentialDriveWheelSpeeds{4.0, 2.0}
63 *
64 * @param other The DifferentialDriveWheelSpeeds to subtract.
65 *
66 * @return The difference between the two DifferentialDriveWheelSpeeds.
67 */
69 const DifferentialDriveWheelSpeeds& other) const {
70 return *this + -other;
71 }
72
73 /**
74 * Returns the inverse of the current DifferentialDriveWheelSpeeds.
75 * This is equivalent to negating all components of the
76 * DifferentialDriveWheelSpeeds.
77 *
78 * @return The inverse of the current DifferentialDriveWheelSpeeds.
79 */
81 return {-left, -right};
82 }
83
84 /**
85 * Multiplies the DifferentialDriveWheelSpeeds by a scalar and returns the new
86 * DifferentialDriveWheelSpeeds.
87 *
88 * <p>For example, DifferentialDriveWheelSpeeds{2.0, 2.5} * 2
89 * = DifferentialDriveWheelSpeeds{4.0, 5.0}
90 *
91 * @param scalar The scalar to multiply by.
92 *
93 * @return The scaled DifferentialDriveWheelSpeeds.
94 */
96 return {scalar * left, scalar * right};
97 }
98
99 /**
100 * Divides the DifferentialDriveWheelSpeeds by a scalar and returns the new
101 * DifferentialDriveWheelSpeeds.
102 *
103 * <p>For example, DifferentialDriveWheelSpeeds{2.0, 2.5} / 2
104 * = DifferentialDriveWheelSpeeds{1.0, 1.25}
105 *
106 * @param scalar The scalar to divide by.
107 *
108 * @return The scaled DifferentialDriveWheelSpeeds.
109 */
111 return operator*(1.0 / scalar);
112 }
113};
114} // namespace frc
115
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Definition: AprilTagPoseEstimator.h:15
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510
constexpr auto operator*(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept -> unit_t< compound_unit< squared< typename units::traits::unit_t_traits< UnitTypeLhs >::unit_type > > >
Multiplication type for convertible unit_t types with a linear scale.
Definition: base.h:2588
Represents the wheel speeds for a differential drive drivetrain.
Definition: DifferentialDriveWheelSpeeds.h:15
constexpr DifferentialDriveWheelSpeeds operator+(const DifferentialDriveWheelSpeeds &other) const
Adds two DifferentialDriveWheelSpeeds and returns the sum.
Definition: DifferentialDriveWheelSpeeds.h:51
units::meters_per_second_t left
Speed of the left side of the robot.
Definition: DifferentialDriveWheelSpeeds.h:19
void Desaturate(units::meters_per_second_t attainableMaxSpeed)
Renormalizes the wheel speeds if either side is above the specified maximum.
constexpr DifferentialDriveWheelSpeeds operator*(double scalar) const
Multiplies the DifferentialDriveWheelSpeeds by a scalar and returns the new DifferentialDriveWheelSpe...
Definition: DifferentialDriveWheelSpeeds.h:95
constexpr DifferentialDriveWheelSpeeds operator/(double scalar) const
Divides the DifferentialDriveWheelSpeeds by a scalar and returns the new DifferentialDriveWheelSpeeds...
Definition: DifferentialDriveWheelSpeeds.h:110
constexpr DifferentialDriveWheelSpeeds operator-() const
Returns the inverse of the current DifferentialDriveWheelSpeeds.
Definition: DifferentialDriveWheelSpeeds.h:80
constexpr DifferentialDriveWheelSpeeds operator-(const DifferentialDriveWheelSpeeds &other) const
Subtracts the other DifferentialDriveWheelSpeeds from the current DifferentialDriveWheelSpeeds and re...
Definition: DifferentialDriveWheelSpeeds.h:68
units::meters_per_second_t right
Speed of the right side of the robot.
Definition: DifferentialDriveWheelSpeeds.h:24