WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
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> &&
24 std::assignable_from<WheelPositions&, const WheelPositions&>
26 public:
27 virtual ~Kinematics() noexcept = default;
28
29 /**
30 * Performs forward kinematics to return the resulting chassis speed from the
31 * wheel speeds. This method is often used for odometry -- determining the
32 * robot's position on the field using data from the real-world speed of each
33 * wheel on the robot.
34 *
35 * @param wheelSpeeds The speeds of the wheels.
36 * @return The chassis speed.
37 */
38 virtual ChassisSpeeds ToChassisSpeeds(
39 const WheelSpeeds& wheelSpeeds) const = 0;
40
41 /**
42 * Performs inverse kinematics to return the wheel speeds from a desired
43 * chassis velocity. This method is often used to convert joystick values into
44 * wheel speeds.
45 *
46 * @param chassisSpeeds The desired chassis speed.
47 * @return The wheel speeds.
48 */
49 virtual WheelSpeeds ToWheelSpeeds(
50 const ChassisSpeeds& chassisSpeeds) const = 0;
51
52 /**
53 * Performs forward kinematics to return the resulting Twist2d from the given
54 * change in wheel positions. This method is often used for odometry --
55 * determining the robot's position on the field using changes in the distance
56 * driven by each wheel on the robot.
57 *
58 * @param start The starting distances driven by the wheels.
59 * @param end The ending distances driven by the wheels.
60 *
61 * @return The resulting Twist2d in the robot's movement.
62 */
63 virtual Twist2d ToTwist2d(const WheelPositions& start,
64 const WheelPositions& end) const = 0;
65
66 /**
67 * Performs interpolation between two values.
68 *
69 * @param start The value to start at.
70 * @param end The value to end at.
71 * @param t How far between the two values to interpolate. This should be
72 * bounded to [0, 1].
73 * @return The interpolated value.
74 */
75 virtual WheelPositions Interpolate(const WheelPositions& start,
76 const WheelPositions& end,
77 double t) const = 0;
78};
79} // 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:25
virtual ~Kinematics() noexcept=default
Definition CAN.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:22