WPILibC++ 2023.4.3
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 <wpi/SymbolExports.h>
8
12#include "units/angle.h"
13#include "units/length.h"
14#include "wpimath/MathShared.h"
15
16namespace frc {
17/**
18 * Helper class that converts a chassis velocity (dx and dtheta components) to
19 * left and right wheel velocities for a differential drive.
20 *
21 * Inverse kinematics converts a desired chassis speed into left and right
22 * velocity components whereas forward kinematics converts left and right
23 * component velocities into a linear and angular chassis speed.
24 */
26 public:
27 /**
28 * Constructs a differential drive kinematics object.
29 *
30 * @param trackWidth The track width of the drivetrain. Theoretically, this is
31 * the distance between the left wheels and right wheels. However, the
32 * empirical value may be larger than the physical measured value due to
33 * scrubbing effects.
34 */
35 explicit DifferentialDriveKinematics(units::meter_t trackWidth)
36 : trackWidth(trackWidth) {
39 }
40
41 /**
42 * Returns a chassis speed from left and right component velocities using
43 * forward kinematics.
44 *
45 * @param wheelSpeeds The left and right velocities.
46 * @return The chassis speed.
47 */
49 const DifferentialDriveWheelSpeeds& wheelSpeeds) const {
50 return {(wheelSpeeds.left + wheelSpeeds.right) / 2.0, 0_mps,
51 (wheelSpeeds.right - wheelSpeeds.left) / trackWidth * 1_rad};
52 }
53
54 /**
55 * Returns left and right component velocities from a chassis speed using
56 * inverse kinematics.
57 *
58 * @param chassisSpeeds The linear and angular (dx and dtheta) components that
59 * represent the chassis' speed.
60 * @return The left and right velocities.
61 */
63 const ChassisSpeeds& chassisSpeeds) const {
64 return {chassisSpeeds.vx - trackWidth / 2 * chassisSpeeds.omega / 1_rad,
65 chassisSpeeds.vx + trackWidth / 2 * chassisSpeeds.omega / 1_rad};
66 }
67
68 /**
69 * Returns a twist from left and right distance deltas using
70 * forward kinematics.
71 *
72 * @param leftDistance The distance measured by the left encoder.
73 * @param rightDistance The distance measured by the right encoder.
74 * @return The resulting Twist2d.
75 */
76 constexpr Twist2d ToTwist2d(const units::meter_t leftDistance,
77 const units::meter_t rightDistance) const {
78 return {(leftDistance + rightDistance) / 2, 0_m,
79 (rightDistance - leftDistance) / trackWidth * 1_rad};
80 }
81
82 units::meter_t trackWidth;
83};
84} // namespace frc
#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:25
units::meter_t trackWidth
Definition: DifferentialDriveKinematics.h:82
constexpr ChassisSpeeds ToChassisSpeeds(const DifferentialDriveWheelSpeeds &wheelSpeeds) const
Returns a chassis speed from left and right component velocities using forward kinematics.
Definition: DifferentialDriveKinematics.h:48
constexpr DifferentialDriveWheelSpeeds ToWheelSpeeds(const ChassisSpeeds &chassisSpeeds) const
Returns left and right component velocities from a chassis speed using inverse kinematics.
Definition: DifferentialDriveKinematics.h:62
DifferentialDriveKinematics(units::meter_t trackWidth)
Constructs a differential drive kinematics object.
Definition: DifferentialDriveKinematics.h:35
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:76
static void ReportUsage(MathUsageId id, int count)
Definition: MathShared.h:73
Definition: AprilTagFieldLayout.h:22
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
units::meters_per_second_t vx
Represents forward velocity w.r.t the robot frame of reference.
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 speeds for a differential drive drivetrain.
Definition: DifferentialDriveWheelSpeeds.h:15
units::meters_per_second_t left
Speed of the left side of the robot.
Definition: DifferentialDriveWheelSpeeds.h:19
units::meters_per_second_t right
Speed of the right side of the robot.
Definition: DifferentialDriveWheelSpeeds.h:24
A change in distance along a 2D arc since the last pose update.
Definition: Twist2d.h:21