WPILibC++ 2025.0.0-alpha-1-14-g3b6f38d
Kinematics.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
11
12namespace frc {
13/**
14 * Helper class that converts a chassis velocity (dx, dy, and dtheta components)
15 * into individual wheel speeds. Robot code should not use this directly-
16 * Instead, use the particular type for your drivetrain (e.g.,
17 * DifferentialDriveKinematics).
18 *
19 * Inverse kinematics converts a desired chassis speed into wheel speeds whereas
20 * forward kinematics converts wheel speeds into chassis speed.
21 */
22template <typename WheelSpeeds, typename WheelPositions>
23 requires std::copy_constructible<WheelPositions>
25 public:
26 /**
27 * Performs forward kinematics to return the resulting chassis speed from the
28 * wheel speeds. This method is often used for odometry -- determining the
29 * robot's position on the field using data from the real-world speed of each
30 * wheel on the robot.
31 *
32 * @param wheelSpeeds The speeds of the wheels.
33 * @return The chassis speed.
34 */
36 const WheelSpeeds& wheelSpeeds) const = 0;
37
38 /**
39 * Performs inverse kinematics to return the wheel speeds from a desired
40 * chassis velocity. This method is often used to convert joystick values into
41 * wheel speeds.
42 *
43 * @param chassisSpeeds The desired chassis speed.
44 * @return The wheel speeds.
45 */
46 virtual WheelSpeeds ToWheelSpeeds(
47 const ChassisSpeeds& chassisSpeeds) const = 0;
48
49 /**
50 * Performs forward kinematics to return the resulting Twist2d from the given
51 * change in wheel positions. This method is often used for odometry --
52 * determining the robot's position on the field using changes in the distance
53 * driven by each wheel on the robot.
54 *
55 * @param start The starting distances driven by the wheels.
56 * @param end The ending distances driven by the wheels.
57 *
58 * @return The resulting Twist2d in the robot's movement.
59 */
60 virtual Twist2d ToTwist2d(const WheelPositions& start,
61 const WheelPositions& end) const = 0;
62
63 /**
64 * Performs interpolation between two values.
65 *
66 * @param start The value to start at.
67 * @param end The value to end at.
68 * @param t How far between the two values to interpolate. This should be
69 * bounded to [0, 1].
70 * @return The interpolated value.
71 */
73 const WheelPositions& end,
74 double t) const = 0;
75};
76} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: Kinematics.h:24
virtual WheelPositions Interpolate(const WheelPositions &start, const WheelPositions &end, double t) const =0
Performs interpolation between two values.
virtual Twist2d ToTwist2d(const WheelPositions &start, const WheelPositions &end) const =0
Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
virtual ChassisSpeeds ToChassisSpeeds(const WheelSpeeds &wheelSpeeds) const =0
Performs forward kinematics to return the resulting chassis speed from the wheel speeds.
virtual WheelSpeeds ToWheelSpeeds(const ChassisSpeeds &chassisSpeeds) const =0
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
Definition: WheelPositions.h:11
Definition: AprilTagDetector_cv.h:11
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
A change in distance along a 2D arc since the last pose update.
Definition: Twist2d.h:21