Gazebo Math

API Reference

7.4.0
Pose3< T > Class Template Reference

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. More...
 
 Pose3 (const Pose3< T > &_pose)=default
 Copy constructor. More...
 
 Pose3 (const Vector3< T > &_pos, const Quaternion< T > &_rot)
 Create a Pose3 based on a position and rotation. More...
 
 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. More...
 
 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. More...
 
 ~Pose3 ()=default
 Destructor. More...
 
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. More...
 
Vector3< T > CoordPositionAdd (const Pose3< T > &_pose) const
 Add one pose to another: result = this + pose. More...
 
Vector3< T > CoordPositionAdd (const Vector3< T > &_pos) const
 Add one point to a vector: result = this + pos. More...
 
Vector3< T > CoordPositionSub (const Pose3< T > &_pose) const
 Subtract one position from another: result = this - pose. More...
 
Quaternion< T > CoordRotationAdd (const Quaternion< T > &_rot) const
 Add one rotation to another: result = this->q + rot. More...
 
Quaternion< T > CoordRotationSub (const Quaternion< T > &_rot) const
 Subtract one rotation from another: result = this->q - rot. More...
 
void Correct ()
 Fix any nan values. More...
 
bool Equal (const Pose3 &_p, const T &_tol) const
 Equality test with tolerance. More...
 
Pose3< T > Inverse () const
 Get the inverse of this pose. More...
 
bool IsFinite () const
 See if a pose is finite (e.g., not nan) More...
 
bool operator!= (const Pose3< T > &_pose) const
 Inequality operator. More...
 
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). More...
 
const Pose3< T > & operator*= (const Pose3< T > &_pose)
 Multiplication assignment operator. This pose will become equal to this * _pose. More...
 
Pose3< T > operator+ (const Pose3< T > &_pose) const
 Addition operator. A is the transform from O to P specified in frame O B is the transform from P to Q specified in frame P then, B + A is the transform from O to Q specified in frame O. More...
 
const Pose3< T > & operator+= (const Pose3< T > &_pose)
 Addition assignment operator. More...
 
Pose3< T > operator- () const
 Negation operator. A is the transform from O to P in frame O then -A is transform from P to O specified in frame P. More...
 
Pose3< T > operator- (const Pose3< T > &_pose) const
 Subtraction operator. A is the transform from O to P in frame O B is the transform from O to Q in frame O B - A is the transform from P to Q in frame P. More...
 
const Pose3< T > & operator-= (const Pose3< T > &_pose)
 Subtraction assignment operator. More...
 
Pose3< T > & operator= (const Pose3< T > &_pose)=default
 Assignment operator. More...
 
bool operator== (const Pose3< T > &_pose) const
 Equality operator. More...
 
const T Pitch () const
 Get the Pitch value of the rotation. More...
 
Vector3< T > & Pos ()
 Get a mutable reference to the position. More...
 
const Vector3< T > & Pos () const
 Get the position. More...
 
void Reset ()
 Reset the pose. This sets the position to zero and the rotation to identify. More...
 
const T Roll () const
 Get the Roll value of the rotation. More...
 
Quaternion< T > & Rot ()
 Get a mutable reference to the rotation. More...
 
const Quaternion< T > & Rot () const
 Get the rotation. More...
 
Pose3< T > RotatePositionAboutOrigin (const Quaternion< T > &_q) const
 Rotate the vector part of a pose about the origin. More...
 
void Round (int _precision)
 Round all values to _precision decimal places. More...
 
void Set (const Vector3< T > &_pos, const Quaternion< T > &_rot)
 Set the pose from a Vector3<T> and a Quaternion<T> More...
 
void Set (const Vector3< T > &_pos, const Vector3< T > &_rpy)
 Set the pose from a position and Euler angles. More...
 
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. More...
 
void SetX (T x)
 Set X value of the position. More...
 
void SetY (T y)
 Set the Y value of the position. More...
 
void SetZ (T z)
 Set the Z value of the position. More...
 
const T X () const
 Get the X value of the position. More...
 
const T Y () const
 Get the Y value of the position. More...
 
const T Yaw () const
 Get the Yaw value of the rotation. More...
 
const T Z () const
 Get the Z value of the position. More...
 

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). More...
 

Detailed Description

template<typename T>
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++
#include <iostream>
#include <gz/math/Pose3.hh>
int main(int argc, char **argv)
{
// Construct a default Pose3d.
std::cout << "A default Pose3d has the following values\n"
<< p << std::endl;
// Construct a pose at position 1, 2, 3 with a yaw of PI radians.
gz::math::Pose3d p1(1, 2, 3, 0, 0, GZ_PI);
std::cout << "A pose3d(1, 2, 3, 0, 0, GZ_PI) has the following values\n"
<< p1 << std::endl;
// Set the position of a pose to 10, 20, 30
p.Pos().Set(10, 20, 30);
// Combine two poses, and store the result in a new pose
gz::math::Pose3d p3 = p * p1;
std::cout << "Result of adding two poses together is\n"
<< p3 << std::endl;
}
  • Ruby
# $ export RUBYLIB=/usr/lib/ruby:$RUBYLIB
#
require 'gz/math'
# Construct a default Pose3d.
p = Gz::Math::Pose3d.new
printf("A default Pose3d has the following values\n" +
"%f %f %f %f %f %f\n", p.Pos().X(), p.Pos().Y(), p.Pos().Z(),
p.Rot().Euler().X(), p.Rot().Euler().Y(), p.Rot().Euler().Z())
# Construct a pose at position 1, 2, 3 with a yaw of PI radians.
p1 = Gz::Math::Pose3d.new(1, 2, 3, 0, 0, Math::PI)
printf("A pose3d(1, 2, 3, 0, 0, GZ_PI) has the following values\n" +
"%f %f %f %f %f %f\n", p1.Pos().X(), p1.Pos().Y(), p1.Pos().Z(),
p1.Rot().Euler().X(), p1.Rot().Euler().Y(), p1.Rot().Euler().Z())
# Set the position of a pose to 10, 20, 30
p.Pos().Set(10, 20, 30)
p3 = p * p1
printf("Result of combining two poses is\n"+
"%f %f %f %f %f %f\n", p3.Pos().X(), p3.Pos().Y(), p3.Pos().Z(),
p3.Rot().Euler().X(), p3.Rot().Euler().Y(), p3.Rot().Euler().Z())

Constructor & Destructor Documentation

◆ Pose3() [1/5]

Pose3 ( )
default

Default constructor. This initializes the position component to zero and the quaternion to identity.

◆ Pose3() [2/5]

Pose3 ( const Vector3< T > &  _pos,
const Quaternion< T > &  _rot 
)
inline

Create a Pose3 based on a position and rotation.

Parameters
[in]_posThe position
[in]_rotThe rotation

◆ Pose3() [3/5]

Pose3 ( _x,
_y,
_z,
_roll,
_pitch,
_yaw 
)
inline

Create a Pose3 using a 6-tuple consisting of x, y, z, roll, pitch, and yaw.

Parameters
[in]_xx position in meters.
[in]_yy position in meters.
[in]_zz position in meters.
[in]_rollRoll (rotation about X-axis) in radians.
[in]_pitchPitch (rotation about y-axis) in radians.
[in]_yawYaw (rotation about z-axis) in radians.

◆ Pose3() [4/5]

Pose3 ( _x,
_y,
_z,
_qw,
_qx,
_qy,
_qz 
)
inline

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]_xx position in meters.
[in]_yy position in meters.
[in]_zz position in meters.
[in]_qwQuaternion w value.
[in]_qxQuaternion x value.
[in]_qyQuaternion y value.
[in]_qzQuaternion z value.

◆ Pose3() [5/5]

Pose3 ( const Pose3< T > &  _pose)
default

Copy constructor.

Parameters
[in]_posePose3<T> to copy

◆ ~Pose3()

~Pose3 ( )
default

Destructor.

Member Function Documentation

◆ CoordPoseSolve()

Pose3<T> CoordPoseSolve ( const Pose3< T > &  _b) const
inline

Find the inverse of a pose; i.e., if b = this + a, given b and this, find a.

Parameters
[in]_bthe other pose.

References Quaternion::Inverse(), Quaternion::X(), Quaternion::Y(), and Quaternion::Z().

◆ CoordPositionAdd() [1/2]

Vector3<T> CoordPositionAdd ( const Pose3< T > &  _pose) const
inline

Add one pose to another: result = this + pose.

Parameters
[in]_poseThe Pose3<T> to add.
Returns
The resulting position.

References Quaternion::Inverse(), Quaternion::X(), Quaternion::Y(), and Quaternion::Z().

◆ CoordPositionAdd() [2/2]

Vector3<T> CoordPositionAdd ( const Vector3< T > &  _pos) const
inline

Add one point to a vector: result = this + pos.

Parameters
[in]_posPosition to add to this pose
Returns
The resulting position.

References Quaternion::Inverse(), Vector3< T >::X(), Quaternion::X(), Vector3< T >::Y(), Quaternion::Y(), Vector3< T >::Z(), and Quaternion::Z().

Referenced by Pose3< T >::operator*(), Pose3< T >::operator+(), and Pose3< T >::operator+=().

◆ CoordPositionSub()

Vector3<T> CoordPositionSub ( const Pose3< T > &  _pose) const
inline

Subtract one position from another: result = this - pose.

Parameters
[in]_posePose3<T> to subtract
Returns
The resulting position

References Quaternion::Inverse(), Quaternion::X(), Quaternion::Y(), and Quaternion::Z().

Referenced by Pose3< T >::operator-(), and Pose3< T >::operator-=().

◆ CoordRotationAdd()

Quaternion<T> CoordRotationAdd ( const Quaternion< T > &  _rot) const
inline

Add one rotation to another: result = this->q + rot.

Parameters
[in]_rotRotation to add.
Returns
The resulting rotation.

Referenced by Pose3< T >::operator+(), and Pose3< T >::operator+=().

◆ CoordRotationSub()

Quaternion<T> CoordRotationSub ( const Quaternion< T > &  _rot) const
inline

Subtract one rotation from another: result = this->q - rot.

Parameters
[in]_rotThe rotation to subtract.
Returns
The resulting rotation.

References Quaternion::Inverse(), and Quaternion::Normalize().

Referenced by Pose3< T >::operator-(), and Pose3< T >::operator-=().

◆ Correct()

void Correct ( )
inline

Fix any nan values.

References Quaternion::Correct().

◆ Equal()

bool Equal ( const Pose3< T > &  _p,
const T &  _tol 
) const
inline

Equality test with tolerance.

Parameters
[in]_pThe pose to compare this against. Both the position Vector3 and rotation Quaternion are compared.
[in]_tolEquality tolerance.
Returns
True if the position and orientation of the poses are equal within the tolerence specified by _tol.

References Quaternion::Equal().

◆ Inverse()

Pose3<T> Inverse ( ) const
inline

Get the inverse of this pose.

Returns
The inverse pose.

References Quaternion::Inverse().

Referenced by Pose3< T >::operator-().

◆ IsFinite()

bool IsFinite ( ) const
inline

See if a pose is finite (e.g., not nan)

Returns
True if this pose is finite.

References Quaternion::IsFinite().

◆ operator!=()

bool operator!= ( const Pose3< T > &  _pose) const
inline

Inequality operator.

Parameters
[in]_posePose3<T> for comparison.
Returns
True if this pose is not equal to the given pose.

◆ operator*()

Pose3<T> operator* ( const Pose3< T > &  _pose) const
inline

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]_poseThe pose to multiply by.
Returns
The resulting pose.

References Pose3< T >::CoordPositionAdd().

◆ operator*=()

const Pose3<T>& operator*= ( const Pose3< T > &  _pose)
inline

Multiplication assignment operator. This pose will become equal to this * _pose.

Parameters
[in]_posePose3<T> to multiply to this pose
See also
operator*(const Pose3<T> &_pose) const
Returns
The resulting pose

◆ operator+()

Pose3<T> operator+ ( const Pose3< T > &  _pose) const
inline

Addition operator. A is the transform from O to P specified in frame O B is the transform from P to Q specified in frame P then, B + A is the transform from O to Q specified in frame O.

Parameters
[in]_posePose3<T> to add to this pose.
Returns
The resulting pose.

References Pose3< T >::CoordPositionAdd(), and Pose3< T >::CoordRotationAdd().

◆ operator+=()

const Pose3<T>& operator+= ( const Pose3< T > &  _pose)
inline

Addition assignment operator.

Parameters
[in]_posePose3<T> to add to this pose.
See also
operator+(const Pose3<T> &_pose) const.
Returns
The resulting pose.

References Pose3< T >::CoordPositionAdd(), and Pose3< T >::CoordRotationAdd().

◆ operator-() [1/2]

Pose3<T> operator- ( ) const
inline

Negation operator. A is the transform from O to P in frame O then -A is transform from P to O specified in frame P.

Returns
The resulting pose.

References Pose3< T >::Inverse().

◆ operator-() [2/2]

Pose3<T> operator- ( const Pose3< T > &  _pose) const
inline

Subtraction operator. A is the transform from O to P in frame O B is the transform from O to Q in frame O B - A is the transform from P to Q in frame P.

Parameters
[in]_posePose3<T> to subtract from this one.
Returns
The resulting pose.

References Pose3< T >::CoordPositionSub(), and Pose3< T >::CoordRotationSub().

◆ operator-=()

const Pose3<T>& operator-= ( const Pose3< T > &  _pose)
inline

Subtraction assignment operator.

Parameters
[in]_posePose3<T> to subtract from this one
See also
operator-(const Pose3<T> &_pose) const.
Returns
The resulting pose

References Pose3< T >::CoordPositionSub(), and Pose3< T >::CoordRotationSub().

◆ operator=()

Pose3<T>& operator= ( const Pose3< T > &  _pose)
default

Assignment operator.

Parameters
[in]_posePose3<T> to copy

◆ operator==()

bool operator== ( const Pose3< T > &  _pose) const
inline

Equality operator.

Parameters
[in]_posePose3<T> for comparison.
Returns
True if this pose is equal to the given pose.

◆ Pitch()

const T Pitch ( ) const
inline

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.

References Quaternion::Pitch().

◆ Pos() [1/2]

Vector3<T>& Pos ( )
inline

Get a mutable reference to the position.

Returns
Origin of the pose.

◆ Pos() [2/2]

const Vector3<T>& Pos ( ) const
inline

Get the position.

Returns
Origin of the pose.

Referenced by gz::math::eigen3::convert(), Matrix4< T >::Matrix4(), and gz::math::eigen3::verticesToOrientedBox().

◆ Reset()

void Reset ( )
inline

Reset the pose. This sets the position to zero and the rotation to identify.

◆ Roll()

const T Roll ( ) const
inline

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.

References Quaternion::Roll().

◆ Rot() [1/2]

Quaternion<T>& Rot ( )
inline

Get a mutable reference to the rotation.

Returns
Quaternion representation of the rotation.

◆ Rot() [2/2]

const Quaternion<T>& Rot ( ) const
inline

Get the rotation.

Returns
Quaternion representation of the rotation.

Referenced by gz::math::eigen3::convert(), and gz::math::eigen3::verticesToOrientedBox().

◆ RotatePositionAboutOrigin()

Pose3<T> RotatePositionAboutOrigin ( const Quaternion< T > &  _q) const
inline

Rotate the vector part of a pose about the origin.

Parameters
[in]_qrotation.
Returns
The rotated pose.

References Quaternion::W(), Quaternion::X(), Quaternion::Y(), and Quaternion::Z().

◆ Round()

void Round ( int  _precision)
inline

Round all values to _precision decimal places.

Parameters
[in]_precisionNumber of decimal places.

References Quaternion::Round().

◆ Set() [1/3]

void Set ( const Vector3< T > &  _pos,
const Quaternion< T > &  _rot 
)
inline

Set the pose from a Vector3<T> and a Quaternion<T>

Parameters
[in]_posThe position.
[in]_rotThe rotation.

◆ Set() [2/3]

void Set ( const Vector3< T > &  _pos,
const Vector3< T > &  _rpy 
)
inline

Set the pose from a position and Euler angles.

Parameters
[in]_posThe position.
[in]_rpyThe rotation expressed as Euler angles.

References Quaternion::SetFromEuler().

◆ Set() [3/3]

void Set ( _x,
_y,
_z,
_roll,
_pitch,
_yaw 
)
inline

Set the pose from a six tuple consisting of x, y, z, roll, pitch, and yaw.

Parameters
[in]_xx position in meters.
[in]_yy position in meters.
[in]_zz position in meters.
[in]_rollRoll (rotation about X-axis) in radians.
[in]_pitchPitch (rotation about y-axis) in radians.
[in]_yawPitch (rotation about z-axis) in radians.

References Quaternion::SetFromEuler().

◆ SetX()

void SetX ( x)
inline

Set X value of the position.

◆ SetY()

void SetY ( y)
inline

Set the Y value of the position.

◆ SetZ()

void SetZ ( z)
inline

Set the Z value of the position.

◆ X()

const T X ( ) const
inline

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()

const T Y ( ) const
inline

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()

const T Yaw ( ) const
inline

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.

References Quaternion::Yaw().

◆ Z()

const T Z ( ) const
inline

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

const Pose3< T > & Zero = detail::gPose3Zero<T>
static

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: