WPILibC++ 2027.0.0-alpha-3
Loading...
Searching...
No Matches
frc::Twist2d Struct Reference

A change in distance along a 2D arc since the last pose update. More...

#include <frc/geometry/Twist2d.h>

Public Member Functions

constexpr Transform2d Exp () const
 Obtain a new Transform2d from a (constant curvature) velocity.
 
constexpr bool operator== (const Twist2d &other) const
 Checks equality between this Twist2d and another object.
 
constexpr Twist2d operator* (double factor) const
 Scale this by a given factor.
 

Public Attributes

units::meter_t dx = 0_m
 Linear "dx" component.
 
units::meter_t dy = 0_m
 Linear "dy" component.
 
units::radian_t dtheta = 0_rad
 Angular "dtheta" component (radians)
 

Detailed Description

A change in distance along a 2D arc since the last pose update.

We can use ideas from differential calculus to create new Pose2ds from a Twist2d and vice versa.

A Twist can be used to represent a difference between two poses.

Member Function Documentation

◆ Exp()

Transform2d frc::Twist2d::Exp ( ) const
constexpr

Obtain a new Transform2d from a (constant curvature) velocity.

See "https://file.tavsys.net/control/controls-engineering-in-frc.pdf" Controls Engineering in the FIRST Robotics Competition section 10.2 "Pose exponential" for a derivation.

The twist is a change in pose in the robot's coordinate frame since the previous pose update. When the user runs Exp() on the twist, the user will receive the pose delta.

"Exp" represents the pose exponential, which is solving a differential equation moving the pose forward in time.

Returns
The pose delta of the robot.

◆ operator*()

Twist2d frc::Twist2d::operator* ( double factor) const
inlineconstexpr

Scale this by a given factor.

Parameters
factorThe factor by which to scale.
Returns
The scaled Twist2d.

◆ operator==()

bool frc::Twist2d::operator== ( const Twist2d & other) const
inlineconstexpr

Checks equality between this Twist2d and another object.

Parameters
otherThe other object.
Returns
Whether the two objects are equal.

Member Data Documentation

◆ dtheta

units::radian_t frc::Twist2d::dtheta = 0_rad

Angular "dtheta" component (radians)

◆ dx

units::meter_t frc::Twist2d::dx = 0_m

Linear "dx" component.

◆ dy

units::meter_t frc::Twist2d::dy = 0_m

Linear "dy" component.


The documentation for this struct was generated from the following file: