Quaternion orientation information. More...
#include <Orientation.h>
Public Member Functions | |
double | getW () const |
W value accessor. | |
double | getX () const |
X value accessor. | |
double | getY () const |
Y value accessor. | |
double | getZ () const |
Z value accessor. | |
Orientation (const double x=0, const double y=0, const double z=0, const double w=0) | |
Create a new Orientation. | |
Orientation (const geometry_msgs::Quaternion &quaternion) | |
Create a new Orientation. | |
Orientation (const tf2::Quaternion &quaternion) | |
Create a new Orientation. | |
void | setW (const double w) |
W value mutator. | |
void | setX (const double x) |
X value mutator. | |
void | setY (const double y) |
Y value mutator. | |
void | setZ (const double z) |
Z value mutator. | |
geometry_msgs::Quaternion | toROSQuaternionMessage () const |
tf2::Matrix3x3 | toTF2Matrix3x3 () const |
tf2::Quaternion | toTF2Quaternion () const |
Private Attributes | |
double | w_ |
double | x_ |
double | y_ |
double | z_ |
Quaternion orientation information.
An orientation simply contains x, y, z, and w values. This class is useful for internal data management within the graspdb library. Convenience functions are added for use with ROS messages.
Definition at line 37 of file Orientation.h.
Orientation::Orientation | ( | const double | x = 0 , |
const double | y = 0 , |
||
const double | z = 0 , |
||
const double | w = 0 |
||
) |
Create a new Orientation.
Creates a new Orientation with the given x, y, z, and w values (defaults are 0).
x | The x value (default of 0). |
y | The y value (default of 0). |
z | The z value (default of 0). |
w | The w value (default of 0). |
Definition at line 18 of file Orientation.cpp.
Orientation::Orientation | ( | const geometry_msgs::Quaternion & | quaternion | ) |
Create a new Orientation.
Creates a new Orientation with the given x, y, z, and w values from the ROS Quaternion message.
point | The ROS Quaternion message to extract values from. |
Definition at line 27 of file Orientation.cpp.
Orientation::Orientation | ( | const tf2::Quaternion & | quaternion | ) |
Create a new Orientation.
Creates a new Orientation with the given x, y, z, and w values from the ROS tf2 Quaternion.
point | The ROS tf2 Quaternion to extract values from. |
Definition at line 36 of file Orientation.cpp.
double Orientation::getW | ( | ) | const |
W value accessor.
Get the w value of this Position.
Definition at line 80 of file Orientation.cpp.
double Orientation::getX | ( | ) | const |
X value accessor.
Get the x value of this Position.
Definition at line 50 of file Orientation.cpp.
double Orientation::getY | ( | ) | const |
Y value accessor.
Get the y value of this Position.
Definition at line 60 of file Orientation.cpp.
double Orientation::getZ | ( | ) | const |
Z value accessor.
Get the z value of this Position.
Definition at line 70 of file Orientation.cpp.
void Orientation::setW | ( | const double | w | ) |
W value mutator.
Set the w value of this Position.
w | The new w value. |
Definition at line 75 of file Orientation.cpp.
void Orientation::setX | ( | const double | x | ) |
X value mutator.
Set the x value of this Position.
x | The new x value. |
Definition at line 45 of file Orientation.cpp.
void Orientation::setY | ( | const double | y | ) |
Y value mutator.
Set the y value of this Position.
y | The new y value. |
Definition at line 55 of file Orientation.cpp.
void Orientation::setZ | ( | const double | z | ) |
Z value mutator.
Set the z value of this Position.
z | The new z value. |
Definition at line 65 of file Orientation.cpp.
geometry_msgs::Quaternion Orientation::toROSQuaternionMessage | ( | ) | const |
Converts this Orientation object into a ROS Quaternion message.
Definition at line 85 of file Orientation.cpp.
tf2::Matrix3x3 Orientation::toTF2Matrix3x3 | ( | ) | const |
Converts this Orientation object into a ROS tf2 Matrix3x3.
Definition at line 101 of file Orientation.cpp.
tf2::Quaternion Orientation::toTF2Quaternion | ( | ) | const |
Converts this Orientation object into a ROS tf2 Quaternion.
Definition at line 95 of file Orientation.cpp.
double rail::pick_and_place::graspdb::Orientation::w_ [private] |
Definition at line 165 of file Orientation.h.
double rail::pick_and_place::graspdb::Orientation::x_ [private] |
Members to hold values.
Definition at line 165 of file Orientation.h.
double rail::pick_and_place::graspdb::Orientation::y_ [private] |
Definition at line 165 of file Orientation.h.
double rail::pick_and_place::graspdb::Orientation::z_ [private] |
Definition at line 165 of file Orientation.h.