WPILibC++ 2024.3.2
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/**
15 * A change in distance along a 2D arc since the last pose update. We can use
16 * ideas from differential calculus to create new Pose2ds from a Twist2d and
17 * vice versa.
18 *
19 * A Twist can be used to represent a difference between two poses.
20 */
22 /**
23 * Linear "dx" component
24 */
25 units::meter_t dx = 0_m;
26
27 /**
28 * Linear "dy" component
29 */
30 units::meter_t dy = 0_m;
31
32 /**
33 * Angular "dtheta" component (radians)
34 */
35 units::radian_t dtheta = 0_rad;
36
37 /**
38 * Checks equality between this Twist2d and another object.
39 *
40 * @param other The other object.
41 * @return Whether the two objects are equal.
42 */
43 bool operator==(const Twist2d& other) const {
44 return units::math::abs(dx - other.dx) < 1E-9_m &&
45 units::math::abs(dy - other.dy) < 1E-9_m &&
46 units::math::abs(dtheta - other.dtheta) < 1E-9_rad;
47 }
48
49 /**
50 * Scale this by a given factor.
51 *
52 * @param factor The factor by which to scale.
53 * @return The scaled Twist2d.
54 */
55 constexpr Twist2d operator*(double factor) const {
56 return Twist2d{dx * factor, dy * factor, dtheta * factor};
57 }
58};
59} // namespace frc
60
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition: math.h:721
Definition: AprilTagPoseEstimator.h:15
A change in distance along a 2D arc since the last pose update.
Definition: Twist2d.h:21
units::meter_t dy
Linear "dy" component.
Definition: Twist2d.h:30
constexpr Twist2d operator*(double factor) const
Scale this by a given factor.
Definition: Twist2d.h:55
units::meter_t dx
Linear "dx" component.
Definition: Twist2d.h:25
units::radian_t dtheta
Angular "dtheta" component (radians)
Definition: Twist2d.h:35
bool operator==(const Twist2d &other) const
Checks equality between this Twist2d and another object.
Definition: Twist2d.h:43