WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
Twist2d.hpp
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/units/angle.hpp"
8#include "wpi/units/length.hpp"
9#include "wpi/units/math.hpp"
11
12namespace wpi::math {
13
14class Transform2d;
15
16/**
17 * A change in distance along a 2D arc since the last pose update. We can use
18 * ideas from differential calculus to create new Pose2ds from a Twist2d and
19 * vice versa.
20 *
21 * A Twist can be used to represent a difference between two poses.
22 */
24 /**
25 * Linear "dx" component
26 */
27 wpi::units::meter_t dx = 0_m;
28
29 /**
30 * Linear "dy" component
31 */
32 wpi::units::meter_t dy = 0_m;
33
34 /**
35 * Angular "dtheta" component (radians)
36 */
37 wpi::units::radian_t dtheta = 0_rad;
38
39 /**
40 * Obtain a new Transform2d from a (constant curvature) velocity.
41 *
42 * See "https://file.tavsys.net/control/controls-engineering-in-frc.pdf"
43 * Controls Engineering in the FIRST Robotics Competition</a> section 10.2
44 * "Pose exponential" for a derivation.
45 *
46 * The twist is a change in pose in the robot's coordinate frame since the
47 * previous pose update. When the user runs Exp() on the twist, the user will
48 * receive the pose delta.
49 *
50 * "Exp" represents the pose exponential, which is solving a differential
51 * equation moving the pose forward in time.
52 *
53 * @return The pose delta of the robot.
54 */
55 constexpr Transform2d Exp() const;
56
57 /**
58 * Checks equality between this Twist2d and another object.
59 *
60 * @param other The other object.
61 * @return Whether the two objects are equal.
62 */
63 constexpr bool operator==(const Twist2d& other) const {
64 return wpi::units::math::abs(dx - other.dx) < 1E-9_m &&
65 wpi::units::math::abs(dy - other.dy) < 1E-9_m &&
66 wpi::units::math::abs(dtheta - other.dtheta) < 1E-9_rad;
67 }
68
69 /**
70 * Scale this by a given factor.
71 *
72 * @param factor The factor by which to scale.
73 * @return The scaled Twist2d.
74 */
75 constexpr Twist2d operator*(double factor) const {
76 return Twist2d{dx * factor, dy * factor, dtheta * factor};
77 }
78};
79
80} // namespace wpi::math
81
83
84namespace wpi::math {
85
86constexpr Transform2d Twist2d::Exp() const {
87 const auto theta = dtheta.value();
88 const auto sinTheta = gcem::sin(theta);
89 const auto cosTheta = gcem::cos(theta);
90
91 double s, c;
92 if (gcem::abs(theta) < 1E-9) {
93 s = 1.0 - 1.0 / 6.0 * theta * theta;
94 c = 0.5 * theta;
95 } else {
96 s = sinTheta / theta;
97 c = (1 - cosTheta) / theta;
98 }
99
100 return Transform2d(Translation2d{dx * s - dy * c, dx * c + dy * s},
101 Rotation2d{cosTheta, sinTheta});
102}
103
104} // namespace wpi::math
105
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Represents a transformation for a Pose2d in the pose's frame.
Definition Transform2d.hpp:21
Represents a translation in 2D space.
Definition Translation2d.hpp:30
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr return_t< T > cos(const T x) noexcept
Compile-time cosine function.
Definition cos.hpp:83
constexpr return_t< T > sin(const T x) noexcept
Compile-time sine function.
Definition sin.hpp:85
Definition LinearSystem.hpp:20
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.hpp:23
constexpr Transform2d Exp() const
Obtain a new Transform2d from a (constant curvature) velocity.
Definition Twist2d.hpp:86
constexpr Twist2d operator*(double factor) const
Scale this by a given factor.
Definition Twist2d.hpp:75
wpi::units::meter_t dy
Linear "dy" component.
Definition Twist2d.hpp:32
wpi::units::radian_t dtheta
Angular "dtheta" component (radians).
Definition Twist2d.hpp:37
constexpr bool operator==(const Twist2d &other) const
Checks equality between this Twist2d and another object.
Definition Twist2d.hpp:63
wpi::units::meter_t dx
Linear "dx" component.
Definition Twist2d.hpp:27