WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
DifferentialDriveKinematics.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 <type_traits>
8
9#include <wpi/SymbolExports.h>
10
16#include "units/angle.h"
17#include "units/length.h"
18#include "wpimath/MathShared.h"
19
20namespace frc {
21/**
22 * Helper class that converts a chassis velocity (dx and dtheta components) to
23 * left and right wheel velocities for a differential drive.
24 *
25 * Inverse kinematics converts a desired chassis speed into left and right
26 * velocity components whereas forward kinematics converts left and right
27 * component velocities into a linear and angular chassis speed.
28 */
30 : public Kinematics<DifferentialDriveWheelSpeeds,
31 DifferentialDriveWheelPositions> {
32 public:
33 /**
34 * Constructs a differential drive kinematics object.
35 *
36 * @param trackWidth The track width of the drivetrain. Theoretically, this is
37 * the distance between the left wheels and right wheels. However, the
38 * empirical value may be larger than the physical measured value due to
39 * scrubbing effects.
40 */
41 constexpr explicit DifferentialDriveKinematics(units::meter_t trackWidth)
42 : trackWidth(trackWidth) {
43 if (!std::is_constant_evaluated()) {
46 }
47 }
48
49 /**
50 * Returns a chassis speed from left and right component velocities using
51 * forward kinematics.
52 *
53 * @param wheelSpeeds The left and right velocities.
54 * @return The chassis speed.
55 */
57 const DifferentialDriveWheelSpeeds& wheelSpeeds) const override {
58 return {(wheelSpeeds.left + wheelSpeeds.right) / 2.0, 0_mps,
59 (wheelSpeeds.right - wheelSpeeds.left) / trackWidth * 1_rad};
60 }
61
62 /**
63 * Returns left and right component velocities from a chassis speed using
64 * inverse kinematics.
65 *
66 * @param chassisSpeeds The linear and angular (dx and dtheta) components that
67 * represent the chassis' speed.
68 * @return The left and right velocities.
69 */
71 const ChassisSpeeds& chassisSpeeds) const override {
72 return {chassisSpeeds.vx - trackWidth / 2 * chassisSpeeds.omega / 1_rad,
73 chassisSpeeds.vx + trackWidth / 2 * chassisSpeeds.omega / 1_rad};
74 }
75
76 /**
77 * Returns a twist from left and right distance deltas using
78 * forward kinematics.
79 *
80 * @param leftDistance The distance measured by the left encoder.
81 * @param rightDistance The distance measured by the right encoder.
82 * @return The resulting Twist2d.
83 */
84 constexpr Twist2d ToTwist2d(const units::meter_t leftDistance,
85 const units::meter_t rightDistance) const {
86 return {(leftDistance + rightDistance) / 2, 0_m,
87 (rightDistance - leftDistance) / trackWidth * 1_rad};
88 }
89
90 constexpr Twist2d ToTwist2d(
92 const DifferentialDriveWheelPositions& end) const override {
93 return ToTwist2d(end.left - start.left, end.right - start.right);
94 }
95
98 const DifferentialDriveWheelPositions& end, double t) const override {
99 return start.Interpolate(end, t);
100 }
101
102 /// Differential drive trackwidth.
103 units::meter_t trackWidth;
104};
105} // namespace frc
106
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition DifferentialDriveKinematics.h:31
constexpr DifferentialDriveWheelSpeeds ToWheelSpeeds(const ChassisSpeeds &chassisSpeeds) const override
Returns left and right component velocities from a chassis speed using inverse kinematics.
Definition DifferentialDriveKinematics.h:70
units::meter_t trackWidth
Differential drive trackwidth.
Definition DifferentialDriveKinematics.h:103
constexpr ChassisSpeeds ToChassisSpeeds(const DifferentialDriveWheelSpeeds &wheelSpeeds) const override
Returns a chassis speed from left and right component velocities using forward kinematics.
Definition DifferentialDriveKinematics.h:56
constexpr Twist2d ToTwist2d(const DifferentialDriveWheelPositions &start, const DifferentialDriveWheelPositions &end) const override
Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
Definition DifferentialDriveKinematics.h:90
constexpr DifferentialDriveWheelPositions Interpolate(const DifferentialDriveWheelPositions &start, const DifferentialDriveWheelPositions &end, double t) const override
Performs interpolation between two values.
Definition DifferentialDriveKinematics.h:96
constexpr Twist2d ToTwist2d(const units::meter_t leftDistance, const units::meter_t rightDistance) const
Returns a twist from left and right distance deltas using forward kinematics.
Definition DifferentialDriveKinematics.h:84
constexpr DifferentialDriveKinematics(units::meter_t trackWidth)
Constructs a differential drive kinematics object.
Definition DifferentialDriveKinematics.h:41
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition Kinematics.h:25
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:75
Definition CAN.h:11
Represents the speed of a robot chassis.
Definition ChassisSpeeds.h:25
units::meters_per_second_t vx
Velocity along the x-axis.
Definition ChassisSpeeds.h:29
units::radians_per_second_t omega
Represents the angular velocity of the robot frame.
Definition ChassisSpeeds.h:39
Represents the wheel positions for a differential drive drivetrain.
Definition DifferentialDriveWheelPositions.h:16
Represents the wheel speeds for a differential drive drivetrain.
Definition DifferentialDriveWheelSpeeds.h:16
units::meters_per_second_t left
Speed of the left side of the robot.
Definition DifferentialDriveWheelSpeeds.h:20
units::meters_per_second_t right
Speed of the right side of the robot.
Definition DifferentialDriveWheelSpeeds.h:25
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.h:22