The Pose3 class represents a 3D position and rotation. The position component is a Vector3, and the rotation is a Quaternion. More...
#include <gz/math/Pose3.hh>
Public Member Functions | |
Pose3 ()=default | |
Default constructor. This initializes the position component to zero and the quaternion to identity. | |
Pose3 (const Vector3< T > &_pos, const Quaternion< T > &_rot) | |
Create a Pose3 based on a position and rotation. | |
Pose3 (T _x, T _y, T _z, T _qw, T _qx, T _qy, T _qz) | |
Create a Pose3 using a 7-tuple consisting of x, y, z, qw, qx, qy, qz. The first three values are the position and the last four the rotation represented as a quaternion. | |
Pose3 (T _x, T _y, T _z, T _roll, T _pitch, T _yaw) | |
Create a Pose3 using a 6-tuple consisting of x, y, z, roll, pitch, and yaw. | |
Pose3< T > | CoordPoseSolve (const Pose3< T > &_b) const |
Find the inverse of a pose; i.e., if b = this + a, given b and this, find a. | |
Vector3< T > | CoordPositionAdd (const Pose3< T > &_pose) const |
Add one pose to another: result = this + pose. | |
Vector3< T > | CoordPositionAdd (const Vector3< T > &_pos) const |
Add one point to a vector: result = this + pos. | |
Vector3< T > | CoordPositionSub (const Pose3< T > &_pose) const |
Subtract one position from another: result = this - pose. | |
Quaternion< T > | CoordRotationAdd (const Quaternion< T > &_rot) const |
Add one rotation to another: result = this->q + rot. | |
Quaternion< T > | CoordRotationSub (const Quaternion< T > &_rot) const |
Subtract one rotation from another: result = this->q - rot. | |
void | Correct () |
Fix any nan values. | |
bool | Equal (const Pose3 &_p, const T &_tol) const |
Equality test with tolerance. | |
Pose3< T > | Inverse () const |
Get the inverse of this pose. | |
bool | IsFinite () const |
See if a pose is finite (e.g., not nan) | |
bool | operator!= (const Pose3< T > &_pose) const |
Inequality operator. | |
Pose3< T > | operator* (const Pose3< T > &_pose) const |
Multiplication operator. Given X_OP (frame P relative to O) and X_PQ (frame Q relative to P) then X_OQ = X_OP * X_PQ (frame Q relative to O). | |
const Pose3< T > & | operator*= (const Pose3< T > &_pose) |
Multiplication assignment operator. This pose will become equal to this * _pose. | |
bool | operator== (const Pose3< T > &_pose) const |
Equality operator. | |
const T | Pitch () const |
Get the Pitch value of the rotation. | |
Vector3< T > & | Pos () |
Get a mutable reference to the position. | |
const Vector3< T > & | Pos () const |
Get the position. | |
void | Reset () |
Reset the pose. This sets the position to zero and the rotation to identify. | |
const T | Roll () const |
Get the Roll value of the rotation. | |
Quaternion< T > & | Rot () |
Get a mutable reference to the rotation. | |
const Quaternion< T > & | Rot () const |
Get the rotation. | |
Pose3< T > | RotatePositionAboutOrigin (const Quaternion< T > &_q) const |
Rotate the vector part of a pose about the origin. | |
void | Round (int _precision) |
Round all values to _precision decimal places. | |
void | Set (const Vector3< T > &_pos, const Quaternion< T > &_rot) |
Set the pose from a Vector3<T> and a Quaternion<T> | |
void | Set (const Vector3< T > &_pos, const Vector3< T > &_rpy) |
Set the pose from a position and Euler angles. | |
void | Set (T _x, T _y, T _z, T _roll, T _pitch, T _yaw) |
Set the pose from a six tuple consisting of x, y, z, roll, pitch, and yaw. | |
void | SetX (T x) |
Set X value of the position. | |
void | SetY (T y) |
Set the Y value of the position. | |
void | SetZ (T z) |
Set the Z value of the position. | |
const T | X () const |
Get the X value of the position. | |
const T | Y () const |
Get the Y value of the position. | |
const T | Yaw () const |
Get the Yaw value of the rotation. | |
const T | Z () const |
Get the Z value of the position. | |
Static Public Attributes | |
static const Pose3< T > & | Zero = detail::gPose3Zero<T> |
A Pose3 initialized to zero. This is equivalent to math::Pose3<T>(0, 0, 0, 0, 0, 0). | |
Detailed Description
class gz::math::Pose3< T >
The Pose3 class represents a 3D position and rotation. The position component is a Vector3, and the rotation is a Quaternion.
The following two type definitions are provided:
Examples
- C++
- Ruby
Constructor & Destructor Documentation
◆ Pose3() [1/4]
Default constructor. This initializes the position component to zero and the quaternion to identity.
◆ Pose3() [2/4]
Create a Pose3 based on a position and rotation.
- Parameters
-
[in] _pos The position [in] _rot The rotation
◆ Pose3() [3/4]
Create a Pose3 using a 6-tuple consisting of x, y, z, roll, pitch, and yaw.
- Parameters
-
[in] _x x position in meters. [in] _y y position in meters. [in] _z z position in meters. [in] _roll Roll (rotation about X-axis) in radians. [in] _pitch Pitch (rotation about y-axis) in radians. [in] _yaw Yaw (rotation about z-axis) in radians.
◆ Pose3() [4/4]
Create a Pose3 using a 7-tuple consisting of x, y, z, qw, qx, qy, qz. The first three values are the position and the last four the rotation represented as a quaternion.
- Parameters
-
[in] _x x position in meters. [in] _y y position in meters. [in] _z z position in meters. [in] _qw Quaternion w value. [in] _qx Quaternion x value. [in] _qy Quaternion y value. [in] _qz Quaternion z value.
Member Function Documentation
◆ CoordPoseSolve()
Find the inverse of a pose; i.e., if b = this + a, given b and this, find a.
- Parameters
-
[in] _b the other pose.
◆ CoordPositionAdd() [1/2]
Add one pose to another: result = this + pose.
- Parameters
-
[in] _pose The Pose3<T> to add.
- Returns
- The resulting position.
◆ CoordPositionAdd() [2/2]
Add one point to a vector: result = this + pos.
- Parameters
-
[in] _pos Position to add to this pose
- Returns
- The resulting position.
◆ CoordPositionSub()
Subtract one position from another: result = this - pose.
- Parameters
-
[in] _pose Pose3<T> to subtract
- Returns
- The resulting position
◆ CoordRotationAdd()
|
inline |
Add one rotation to another: result = this->q + rot.
- Parameters
-
[in] _rot Rotation to add.
- Returns
- The resulting rotation.
◆ CoordRotationSub()
|
inline |
Subtract one rotation from another: result = this->q - rot.
- Parameters
-
[in] _rot The rotation to subtract.
- Returns
- The resulting rotation.
◆ Correct()
◆ Equal()
Equality test with tolerance.
- Parameters
-
[in] _p The pose to compare this against. Both the position Vector3 and rotation Quaternion are compared. [in] _tol Equality tolerance.
- Returns
- True if the position and orientation of the poses are equal within the tolerence specified by _tol.
References Matrix6< T >::Equal().
◆ Inverse()
Get the inverse of this pose.
- Returns
- The inverse pose.
◆ IsFinite()
See if a pose is finite (e.g., not nan)
- Returns
- True if this pose is finite.
◆ operator!=()
Inequality operator.
- Parameters
-
[in] _pose Pose3<T> for comparison.
- Returns
- True if this pose is not equal to the given pose.
◆ operator*()
Multiplication operator. Given X_OP (frame P relative to O) and X_PQ (frame Q relative to P) then X_OQ = X_OP * X_PQ (frame Q relative to O).
- Parameters
-
[in] _pose The pose to multiply by.
- Returns
- The resulting pose.
◆ operator*=()
Multiplication assignment operator. This pose will become equal to this * _pose.
- Parameters
-
[in] _pose Pose3<T> to multiply to this pose
- Returns
- The resulting pose
◆ operator==()
Equality operator.
- Parameters
-
[in] _pose Pose3<T> for comparison.
- Returns
- True if this pose is equal to the given pose.
◆ Pitch()
Get the Pitch value of the rotation.
- Returns
- Pitch value of the orientation.
- Note
- The return is made by value since Quaternion<T>.Pitch() is already a reference.
◆ Pos() [1/2]
Get a mutable reference to the position.
- Returns
- Origin of the pose.
◆ Pos() [2/2]
Get the position.
- Returns
- Origin of the pose.
◆ Reset()
Reset the pose. This sets the position to zero and the rotation to identify.
References Matrix6< T >::Set().
◆ Roll()
Get the Roll value of the rotation.
- Returns
- Roll value of the orientation.
- Note
- The return is made by value since Quaternion<T>.Roll() is already a reference.
◆ Rot() [1/2]
|
inline |
Get a mutable reference to the rotation.
- Returns
- Quaternion representation of the rotation.
◆ Rot() [2/2]
|
inline |
Get the rotation.
- Returns
- Quaternion representation of the rotation.
◆ RotatePositionAboutOrigin()
|
inline |
Rotate the vector part of a pose about the origin.
- Parameters
-
[in] _q rotation.
- Returns
- The rotated pose.
◆ Round()
Round all values to _precision decimal places.
- Parameters
-
[in] _precision Number of decimal places.
◆ Set() [1/3]
Set the pose from a Vector3<T> and a Quaternion<T>
- Parameters
-
[in] _pos The position. [in] _rot The rotation.
◆ Set() [2/3]
Set the pose from a position and Euler angles.
- Parameters
-
[in] _pos The position. [in] _rpy The rotation expressed as Euler angles.
◆ Set() [3/3]
Set the pose from a six tuple consisting of x, y, z, roll, pitch, and yaw.
- Parameters
-
[in] _x x position in meters. [in] _y y position in meters. [in] _z z position in meters. [in] _roll Roll (rotation about X-axis) in radians. [in] _pitch Pitch (rotation about y-axis) in radians. [in] _yaw Pitch (rotation about z-axis) in radians.
References Matrix6< T >::Set().
◆ SetX()
◆ SetY()
◆ SetZ()
◆ X()
Get the X value of the position.
- Returns
- Value X of the origin of the pose.
- Note
- The return is made by value since Vector3<T>.X() is already a reference.
◆ Y()
Get the Y value of the position.
- Returns
- Value Y of the origin of the pose.
- Note
- The return is made by value since Vector3<T>.Y() is already a reference.
◆ Yaw()
Get the Yaw value of the rotation.
- Returns
- Yaw value of the orientation.
- Note
- The return is made by value since Quaternion<T>.Yaw() is already a reference.
◆ Z()
Get the Z value of the position.
- Returns
- Value Z of the origin of the pose.
- Note
- The return is made by value since Vector3<T>.Z() is already a reference.
Member Data Documentation
◆ Zero
A Pose3 initialized to zero. This is equivalent to math::Pose3<T>(0, 0, 0, 0, 0, 0).
The documentation for this class was generated from the following file: