Pose Class Reference

Encapsulates a position and rotation in three space. More...

#include <math/gzmath.hh>

Public Member Functions

 Pose ()
 Default constructors. More...
 
 Pose (const Vector3 &_pos, const Quaternion &_rot)
 Constructor. More...
 
 Pose (double _x, double _y, double _z, double _roll, double _pitch, double _yaw)
 Constructor. More...
 
 Pose (const Pose &_pose)
 Copy constructor. More...
 
 Pose (const ignition::math::Pose3d &_pose)
 Copy constructor for ignition math. More...
 
virtual ~Pose ()
 Destructor. More...
 
Pose CoordPoseSolve (const Pose &_b) const
 Find the inverse of a pose; i.e., if b = this + a, given b and this, find a. More...
 
Vector3 CoordPositionAdd (const Vector3 &_pos) const
 Add one point to a vector: result = this + pos. More...
 
Vector3 CoordPositionAdd (const Pose &_pose) const
 Add one point to another: result = this + pose. More...
 
Vector3 CoordPositionSub (const Pose &_pose) const
 Subtract one position from another: result = this - pose. More...
 
Quaternion CoordRotationAdd (const Quaternion &_rot) const
 Add one rotation to another: result = this->rot + rot. More...
 
Quaternion CoordRotationSub (const Quaternion &_rot) const
 Subtract one rotation from another: result = this->rot - rot. More...
 
void Correct ()
 Fix any nan values. More...
 
Pose GetInverse () const
 Get the inverse of this pose. More...
 
ignition::math::Pose3d Ign () const
 Convert this pose to an ignition::math::Pose3d object. More...
 
bool IsFinite () const
 See if a pose is finite (e.g., not nan) More...
 
bool operator!= (const Pose &_pose) const
 Inequality operator. More...
 
Pose operator* (const Pose &_pose)
 Multiplication operator. More...
 
Pose operator+ (const Pose &_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 Poseoperator+= (const Pose &_pose)
 Add-Equals operator. More...
 
Pose 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...
 
Pose operator- (const Pose &_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 Poseoperator-= (const Pose &_pose)
 Subtraction operator. More...
 
Poseoperator= (const Pose &_pose)
 Equal operator. More...
 
Poseoperator= (const ignition::math::Pose3d &_pose)
 Equal operator for ignition math. More...
 
bool operator== (const Pose &_pose) const
 Equality operator. More...
 
void Reset ()
 Reset the pose. More...
 
Pose RotatePositionAboutOrigin (const Quaternion &_rot) const
 Rotate 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 &_pos, const Quaternion &_rot)
 Set the pose from a Vector3 and a Quaternion. More...
 
void Set (const Vector3 &_pos, const Vector3 &_rpy)
 Set the pose from pos and rpy vectors. More...
 
void Set (double _x, double _y, double _z, double _roll, double _pitch, double _yaw)
 Set the pose from a six tuple. More...
 

Public Attributes

Vector3 pos
 The position. More...
 
Quaternion rot
 The rotation. More...
 

Static Public Attributes

static const Pose Zero
 math::Pose(0, 0, 0, 0, 0, 0) More...
 

Friends

std::ostream & operator<< (std::ostream &_out, const gazebo::math::Pose &_pose)
 Stream insertion operator. More...
 
std::istream & operator>> (std::istream &_in, gazebo::math::Pose &_pose)
 Stream extraction operator. More...
 

Detailed Description

Encapsulates a position and rotation in three space.

Constructor & Destructor Documentation

Pose ( )

Default constructors.

Referenced by Pose::operator-().

Pose ( const Vector3 _pos,
const Quaternion _rot 
)

Constructor.

Parameters
[in]_posA position
[in]_rotA rotation
Pose ( double  _x,
double  _y,
double  _z,
double  _roll,
double  _pitch,
double  _yaw 
)

Constructor.

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.
Pose ( const Pose _pose)

Copy constructor.

Parameters
[in]_posePose to copy
Pose ( const ignition::math::Pose3d &  _pose)

Copy constructor for ignition math.

Parameters
[in]_posePose to copy
virtual ~Pose ( )
virtual

Destructor.

Member Function Documentation

Pose CoordPoseSolve ( const Pose _b) const

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

Parameters
[in]_bthe other pose
Vector3 CoordPositionAdd ( const Vector3 _pos) const

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

Parameters
[in]_posPosition to add to this pose
Returns
the resulting position
Vector3 CoordPositionAdd ( const Pose _pose) const

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

Parameters
[in]_poseThe Pose to add
Returns
The resulting position
Vector3 CoordPositionSub ( const Pose _pose) const
inline

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

Parameters
[in]_posePose to subtract
Returns
The resulting position

References Quaternion::GetInverse(), Pose::pos, Pose::rot, Vector3::x, Quaternion::x, Vector3::y, Quaternion::y, Vector3::z, and Quaternion::z.

Referenced by Pose::operator-().

Quaternion CoordRotationAdd ( const Quaternion _rot) const

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

Parameters
[in]_rotRotation to add
Returns
The resulting rotation
Quaternion CoordRotationSub ( const Quaternion _rot) const
inline

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

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

References Quaternion::GetInverse(), Quaternion::Normalize(), and Pose::rot.

Referenced by Pose::operator-().

void Correct ( )
inline

Fix any nan values.

References Vector3::Correct(), Quaternion::Correct(), Pose::pos, and Pose::rot.

Pose GetInverse ( ) const

Get the inverse of this pose.

Returns
the inverse pose
ignition::math::Pose3d Ign ( ) const

Convert this pose to an ignition::math::Pose3d object.

Returns
This pose represented as an ignition::math::Pose3d.
bool IsFinite ( ) const

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

bool operator!= ( const Pose _pose) const

Inequality operator.

Parameters
[in]_posePose for comparison
Returns
True if not equal
Pose operator* ( const Pose _pose)

Multiplication operator.

Parameters
[in]_posethe other pose
Returns
itself
Pose operator+ ( const Pose _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.

Parameters
[in]_posePose to add to this pose
Returns
The resulting pose
const Pose& operator+= ( const Pose _pose)

Add-Equals operator.

Parameters
[in]_posePose to add to this pose
Returns
The resulting pose
Pose 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 Pose::Pose().

Pose operator- ( const Pose _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]_posePose to subtract from this one
Returns
The resulting pose

References Pose::CoordPositionSub(), Pose::CoordRotationSub(), Pose::Pose(), and Pose::rot.

const Pose& operator-= ( const Pose _pose)

Subtraction operator.

Parameters
[in]_posePose to subtract from this one
Returns
The resulting pose
Pose& operator= ( const Pose _pose)

Equal operator.

Parameters
[in]_posePose to copy
Pose& operator= ( const ignition::math::Pose3d &  _pose)

Equal operator for ignition math.

Parameters
[in]_posePose to copy
bool operator== ( const Pose _pose) const

Equality operator.

Parameters
[in]_posePose for comparison
Returns
True if equal
void Reset ( )

Reset the pose.

Pose RotatePositionAboutOrigin ( const Quaternion _rot) const

Rotate vector part of a pose about the origin.

Parameters
[in]_rotrotation
Returns
the rotated pose
void Round ( int  _precision)

Round all values to _precision decimal places.

Parameters
[in]_precision
void Set ( const Vector3 _pos,
const Quaternion _rot 
)

Set the pose from a Vector3 and a Quaternion.

Parameters
[in]_posThe position.
[in]_rotThe rotation.
void Set ( const Vector3 _pos,
const Vector3 _rpy 
)

Set the pose from pos and rpy vectors.

Parameters
[in]_posThe position.
[in]_rpyThe rotation expressed as Euler angles.
void Set ( double  _x,
double  _y,
double  _z,
double  _roll,
double  _pitch,
double  _yaw 
)

Set the pose from a six tuple.

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.

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  _out,
const gazebo::math::Pose _pose 
)
friend

Stream insertion operator.

Parameters
[in]_outoutput stream
[in]_posepose to output
Returns
the stream
std::istream& operator>> ( std::istream &  _in,
gazebo::math::Pose _pose 
)
friend

Stream extraction operator.

Parameters
[in]_inthe input stream
[in]_posethe pose
Returns
the stream

Member Data Documentation

const Pose Zero
static

math::Pose(0, 0, 0, 0, 0, 0)


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