Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.math.geometry.Pose2d Class Reference
Inheritance diagram for edu.wpi.first.math.geometry.Pose2d:
edu.wpi.first.math.interpolation.Interpolatable< T > edu.wpi.first.util.protobuf.ProtobufSerializable edu.wpi.first.util.struct.StructSerializable edu.wpi.first.util.WPISerializable edu.wpi.first.util.WPISerializable

Public Member Functions

 Pose2d ()
 
 Pose2d ( @JsonProperty(required=true, value="translation") Translation2d translation, @JsonProperty(required=true, value="rotation") Rotation2d rotation)
 
 Pose2d (double x, double y, Rotation2d rotation)
 
 Pose2d (Measure< Distance > x, Measure< Distance > y, Rotation2d rotation)
 
Pose2d plus (Transform2d other)
 
Transform2d minus (Pose2d other)
 
Translation2d getTranslation ()
 
double getX ()
 
double getY ()
 
Rotation2d getRotation ()
 
Pose2d times (double scalar)
 
Pose2d div (double scalar)
 
Pose2d rotateBy (Rotation2d other)
 
Pose2d transformBy (Transform2d other)
 
Pose2d relativeTo (Pose2d other)
 
Pose2d exp (Twist2d twist)
 
Twist2d log (Pose2d end)
 
Pose2d nearest (List< Pose2d > poses)
 
boolean equals (Object obj)
 
- Public Member Functions inherited from edu.wpi.first.math.interpolation.Interpolatable< T >
interpolate (T endValue, double t)
 

Static Public Attributes

static final Pose2dProto proto = new Pose2dProto()
 
static final Pose2dStruct struct = new Pose2dStruct()
 

Detailed Description

Represents a 2D pose containing translational and rotational elements.

Constructor & Destructor Documentation

◆ Pose2d() [1/4]

edu.wpi.first.math.geometry.Pose2d.Pose2d ( )

Constructs a pose at the origin facing toward the positive X axis.

◆ Pose2d() [2/4]

edu.wpi.first.math.geometry.Pose2d.Pose2d ( @JsonProperty(required=true, value="translation") Translation2d translation,
@JsonProperty(required=true, value="rotation") Rotation2d rotation )

Constructs a pose with the specified translation and rotation.

Parameters
translationThe translational component of the pose.
rotationThe rotational component of the pose.

◆ Pose2d() [3/4]

edu.wpi.first.math.geometry.Pose2d.Pose2d ( double x,
double y,
Rotation2d rotation )

Constructs a pose with x and y translations instead of a separate Translation2d.

Parameters
xThe x component of the translational component of the pose.
yThe y component of the translational component of the pose.
rotationThe rotational component of the pose.

◆ Pose2d() [4/4]

edu.wpi.first.math.geometry.Pose2d.Pose2d ( Measure< Distance > x,
Measure< Distance > y,
Rotation2d rotation )

Constructs a pose with x and y translations instead of a separate Translation2d. The X and Y translations will be converted to and tracked as meters.

Parameters
xThe x component of the translational component of the pose.
yThe y component of the translational component of the pose.
rotationThe rotational component of the pose.

Member Function Documentation

◆ div()

Pose2d edu.wpi.first.math.geometry.Pose2d.div ( double scalar)

Divides the current pose by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Pose2d.

◆ equals()

boolean edu.wpi.first.math.geometry.Pose2d.equals ( Object obj)

Checks equality between this Pose2d and another object.

Parameters
objThe other object.
Returns
Whether the two objects are equal or not.

◆ exp()

Pose2d edu.wpi.first.math.geometry.Pose2d.exp ( Twist2d twist)

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

See 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 previous known field-relative pose with the argument being the twist, the user will receive the new field-relative pose.

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

Parameters
twistThe change in pose in the robot's coordinate frame since the previous pose update. For example, if a non-holonomic robot moves forward 0.01 meters and changes angle by 0.5 degrees since the previous pose update, the twist would be Twist2d(0.01, 0.0, Units.degreesToRadians(0.5)).
Returns
The new pose of the robot.

◆ getRotation()

Rotation2d edu.wpi.first.math.geometry.Pose2d.getRotation ( )

Returns the rotational component of the transformation.

Returns
The rotational component of the pose.

◆ getTranslation()

Translation2d edu.wpi.first.math.geometry.Pose2d.getTranslation ( )

Returns the translation component of the transformation.

Returns
The translational component of the pose.

◆ getX()

double edu.wpi.first.math.geometry.Pose2d.getX ( )

Returns the X component of the pose's translation.

Returns
The x component of the pose's translation.

◆ getY()

double edu.wpi.first.math.geometry.Pose2d.getY ( )

Returns the Y component of the pose's translation.

Returns
The y component of the pose's translation.

◆ log()

Twist2d edu.wpi.first.math.geometry.Pose2d.log ( Pose2d end)

Returns a Twist2d that maps this pose to the end pose. If c is the output of a.Log(b), then a.Exp(c) would yield b.

Parameters
endThe end pose for the transformation.
Returns
The twist that maps this to end.

◆ minus()

Transform2d edu.wpi.first.math.geometry.Pose2d.minus ( Pose2d other)

Returns the Transform2d that maps the one pose to another.

Parameters
otherThe initial pose of the transformation.
Returns
The transform that maps the other pose to the current pose.

◆ nearest()

Pose2d edu.wpi.first.math.geometry.Pose2d.nearest ( List< Pose2d > poses)

Returns the nearest Pose2d from a list of poses. If two or more poses in the list have the same distance from this pose, return the one with the closest rotation component.

Parameters
posesThe list of poses to find the nearest.
Returns
The nearest Pose2d from the list.

◆ plus()

Pose2d edu.wpi.first.math.geometry.Pose2d.plus ( Transform2d other)

Transforms the pose by the given transformation and returns the new transformed pose.

[x_new]    [cos, -sin, 0][transform.x]
[y_new] += [sin,  cos, 0][transform.y]
[t_new]    [  0,    0, 1][transform.t]
Parameters
otherThe transform to transform the pose by.
Returns
The transformed pose.

◆ relativeTo()

Pose2d edu.wpi.first.math.geometry.Pose2d.relativeTo ( Pose2d other)

Returns the current pose relative to the given pose.

This function can often be used for trajectory tracking or pose stabilization algorithms to get the error between the reference and the current pose.

Parameters
otherThe pose that is the origin of the new coordinate frame that the current pose will be converted into.
Returns
The current pose relative to the new origin pose.

◆ rotateBy()

Pose2d edu.wpi.first.math.geometry.Pose2d.rotateBy ( Rotation2d other)

Rotates the pose around the origin and returns the new pose.

Parameters
otherThe rotation to transform the pose by.
Returns
The transformed pose.

◆ times()

Pose2d edu.wpi.first.math.geometry.Pose2d.times ( double scalar)

Multiplies the current pose by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Pose2d.

◆ transformBy()

Pose2d edu.wpi.first.math.geometry.Pose2d.transformBy ( Transform2d other)

Transforms the pose by the given transformation and returns the new pose. See + operator for the matrix multiplication performed.

Parameters
otherThe transform to transform the pose by.
Returns
The transformed pose.

Member Data Documentation

◆ proto

final Pose2dProto edu.wpi.first.math.geometry.Pose2d.proto = new Pose2dProto()
static

Pose2d protobuf for serialization.

◆ struct

final Pose2dStruct edu.wpi.first.math.geometry.Pose2d.struct = new Pose2dStruct()
static

Pose2d struct for serialization.


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