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