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 Pose & | operator+= (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 Pose & | operator-= (const Pose &_pose) |
Subtraction operator. More... | |
Pose & | operator= (const Pose &_pose) |
Equal operator. More... | |
Pose & | operator= (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... | |
Encapsulates a position and rotation in three space.
Pose | ( | ) |
Default constructors.
Referenced by Pose::operator-().
Pose | ( | const Vector3 & | _pos, |
const Quaternion & | _rot | ||
) |
Constructor.
[in] | _pos | A position |
[in] | _rot | A rotation |
Pose | ( | double | _x, |
double | _y, | ||
double | _z, | ||
double | _roll, | ||
double | _pitch, | ||
double | _yaw | ||
) |
Constructor.
[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. |
Pose | ( | const ignition::math::Pose3d & | _pose | ) |
Copy constructor for ignition math.
[in] | _pose | Pose to copy |
|
virtual |
Destructor.
Find the inverse of a pose; i.e., if b = this + a, given b and this, find a.
[in] | _b | the other pose |
Referenced by Pose::CoordRotationSub().
Add one point to a vector: result = this + pos.
[in] | _pos | Position to add to this pose |
Referenced by Pose::operator-().
Add one point to another: result = this + pose.
[in] | _pose | The Pose to add |
Subtract one position from another: result = this - pose.
[in] | _pose | Pose to subtract |
References Pose::CoordRotationAdd(), 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.
[in] | _rot | Rotation to add |
Referenced by Pose::CoordPositionSub().
|
inline |
Subtract one rotation from another: result = this->rot - rot.
[in] | _rot | The rotation to subtract |
References Pose::CoordPoseSolve(), Quaternion::GetInverse(), Pose::Ign(), Quaternion::Normalize(), Pose::Reset(), Pose::rot, Pose::RotatePositionAboutOrigin(), and Pose::Round().
Referenced by Pose::operator-().
|
inline |
Fix any nan values.
References Vector3::Correct(), Quaternion::Correct(), Pose::GetInverse(), Pose::operator+(), Pose::operator+=(), Pose::pos, and Pose::rot.
Pose GetInverse | ( | ) | const |
ignition::math::Pose3d Ign | ( | ) | const |
Convert this pose to an ignition::math::Pose3d object.
Referenced by Pose::CoordRotationSub().
bool IsFinite | ( | ) | const |
See if a pose is finite (e.g., not nan)
bool operator!= | ( | const Pose & | _pose | ) | const |
Inequality operator.
[in] | _pose | Pose for comparison |
Referenced by Pose::operator-().
Multiplication operator.
[in] | _pose | the other pose |
Referenced by Pose::operator-().
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.
[in] | _pose | Pose to add to this pose |
Referenced by Pose::Correct().
Add-Equals operator.
[in] | _pose | Pose to add to this pose |
Referenced by Pose::Correct().
|
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.
References Pose::Pose().
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.
[in] | _pose | Pose to subtract from this one |
References Pose::CoordPositionAdd(), Pose::CoordPositionSub(), Pose::CoordRotationSub(), Pose::operator!=(), Pose::operator*(), Pose::operator-=(), Pose::operator=(), Pose::operator==(), Pose::Pose(), and Pose::rot.
Subtraction operator.
[in] | _pose | Pose to subtract from this one |
Referenced by Pose::operator-().
Pose& operator= | ( | const ignition::math::Pose3d & | _pose | ) |
Equal operator for ignition math.
[in] | _pose | Pose to copy |
bool operator== | ( | const Pose & | _pose | ) | const |
Equality operator.
[in] | _pose | Pose for comparison |
Referenced by Pose::operator-().
void Reset | ( | ) |
Reset the pose.
Referenced by Pose::CoordRotationSub().
Pose RotatePositionAboutOrigin | ( | const Quaternion & | _rot | ) | const |
Rotate vector part of a pose about the origin.
[in] | _rot | rotation |
Referenced by Pose::CoordRotationSub().
void Round | ( | int | _precision | ) |
Round all values to _precision decimal places.
[in] | _precision |
Referenced by Pose::CoordRotationSub().
void Set | ( | const Vector3 & | _pos, |
const Quaternion & | _rot | ||
) |
Set the pose from a Vector3 and a Quaternion.
[in] | _pos | The position. |
[in] | _rot | The rotation. |
Set the pose from pos and rpy vectors.
[in] | _pos | The position. |
[in] | _rpy | The 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.
[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. |
|
friend |
Stream insertion operator.
[in] | _out | output stream |
[in] | _pose | pose to output |
|
friend |
Stream extraction operator.
[in] | _in | the input stream |
[in] | _pose | the pose |
Vector3 pos |
Quaternion rot |
The rotation.
Referenced by BulletTypes::ConvertPose(), DARTTypes::ConvPose(), Pose::CoordPositionSub(), Pose::CoordRotationSub(), Pose::Correct(), and Pose::operator-().
|
static |
math::Pose(0, 0, 0, 0, 0, 0)