Position provides conversions from common position types. More...
#include <position.h>
Public Member Functions | |
pcl::PointXYZ | pcl_point () const |
Returns this translation as pcl::PointXYZ. | |
geometry_msgs::Point | point () const |
Returns this translation as geometry_msgs::Point. | |
Position () | |
Default constructor, (0, 0, 0). | |
Position (double x, double y, double z) | |
x/y/z constructor. | |
Position (const Eigen::Vector3d &v) | |
Eigen::Vector3d constructor. | |
Position (const geometry_msgs::Point &p) | |
geometry_msgs point constructor. | |
Position (const geometry_msgs::Vector3 &v) | |
geometry_msgs vector constructor. | |
Position (const pcl::PointXYZ &p) | |
PCL point constructor. | |
Position (const tf::Vector3 &v) | |
tf vector constructor. | |
tf::Vector3 | tf_vector3 () const |
Returns this translation as tf::Vector3. | |
Eigen::Vector3d | vector () const |
Returns this translation as an Eigen::Vector3d. | |
geometry_msgs::Vector3 | vector_msg () const |
Returns this translation as geometry_msgs::Vector3. | |
double | x () const |
Returns the x component of this position. | |
double | y () const |
Returns the y component of this position. | |
double | z () const |
Returns the z component of this position. | |
Private Attributes | |
Eigen::Vector3d | vector_ |
Position provides conversions from common position types.
By default it is (0, 0, 0). This class also provides various methods to convert back to common types.
Definition at line 15 of file position.h.
Default constructor, (0, 0, 0).
Definition at line 10 of file position.cpp.
transform_graph::Position::Position | ( | double | x, |
double | y, | ||
double | z | ||
) |
x/y/z constructor.
Definition at line 12 of file position.cpp.
transform_graph::Position::Position | ( | const Eigen::Vector3d & | v | ) |
Eigen::Vector3d constructor.
Definition at line 16 of file position.cpp.
transform_graph::Position::Position | ( | const geometry_msgs::Point & | p | ) |
geometry_msgs point constructor.
Definition at line 18 of file position.cpp.
geometry_msgs vector constructor.
Definition at line 22 of file position.cpp.
transform_graph::Position::Position | ( | const pcl::PointXYZ & | p | ) |
PCL point constructor.
Definition at line 26 of file position.cpp.
transform_graph::Position::Position | ( | const tf::Vector3 & | v | ) |
tf vector constructor.
pcl::PointXYZ transform_graph::Position::pcl_point | ( | ) | const |
Returns this translation as pcl::PointXYZ.
Definition at line 52 of file position.cpp.
Returns this translation as geometry_msgs::Point.
Definition at line 36 of file position.cpp.
Returns this translation as tf::Vector3.
Definition at line 60 of file position.cpp.
Eigen::Vector3d transform_graph::Position::vector | ( | ) | const |
Returns this translation as an Eigen::Vector3d.
Definition at line 34 of file position.cpp.
Returns this translation as geometry_msgs::Vector3.
Definition at line 44 of file position.cpp.
double transform_graph::Position::x | ( | ) | const |
Returns the x component of this position.
Definition at line 65 of file position.cpp.
double transform_graph::Position::y | ( | ) | const |
Returns the y component of this position.
Definition at line 67 of file position.cpp.
double transform_graph::Position::z | ( | ) | const |
Returns the z component of this position.
Definition at line 69 of file position.cpp.
Eigen::Vector3d transform_graph::Position::vector_ [private] |
Definition at line 65 of file position.h.