WPILibC++
2020.3.2
Twist2d.h
1
/*----------------------------------------------------------------------------*/
2
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
3
/* Open Source Software - may be modified and shared by FRC teams. The code */
4
/* must be accompanied by the FIRST BSD license file in the root directory of */
5
/* the project. */
6
/*----------------------------------------------------------------------------*/
7
8
#pragma once
9
#include <units/units.h>
10
11
namespace
frc
{
19
struct
Twist2d
{
23
units::meter_t
dx
= 0_m;
24
28
units::meter_t
dy
= 0_m;
29
33
units::radian_t
dtheta
= 0_rad;
34
41
bool
operator==
(
const
Twist2d
& other)
const
{
42
return
units::math::abs(
dx
- other.
dx
) < 1E-9_m &&
43
units::math::abs(
dy
- other.
dy
) < 1E-9_m &&
44
units::math::abs(
dtheta
- other.
dtheta
) < 1E-9_rad;
45
}
46
53
bool
operator!=
(
const
Twist2d
& other)
const
{
return
!
operator==
(other); }
54
};
55
}
// namespace frc
frc::Twist2d::operator==
bool operator==(const Twist2d &other) const
Checks equality between this Twist2d and another object.
Definition:
Twist2d.h:41
frc::Twist2d
A change in distance along arc since the last pose update.
Definition:
Twist2d.h:19
frc::Twist2d::dy
units::meter_t dy
Linear "dy" component.
Definition:
Twist2d.h:28
frc::Twist2d::dtheta
units::radian_t dtheta
Angular "dtheta" component (radians)
Definition:
Twist2d.h:33
frc::Twist2d::dx
units::meter_t dx
Linear "dx" component.
Definition:
Twist2d.h:23
frc::Twist2d::operator!=
bool operator!=(const Twist2d &other) const
Checks inequality between this Twist2d and another object.
Definition:
Twist2d.h:53
frc
A class that enforces constraints on the differential drive kinematics.
Definition:
SPIAccelerometerSim.h:16
wpilibc
src
main
native
include
frc
geometry
Twist2d.h
Generated on Fri Feb 21 2020 08:50:36 for WPILibC++ by
1.8.16