transform.h
Go to the documentation of this file.
00001 #ifndef _TRANSFORM_GRAPH_TRANSFORM_H_
00002 #define _TRANSFORM_GRAPH_TRANSFORM_H_
00003 
00004 #include "Eigen/Dense"
00005 #include "Eigen/Geometry"
00006 #include "geometry_msgs/Pose.h"
00007 #include "geometry_msgs/Transform.h"
00008 #include "tf/transform_datatypes.h"
00009 
00010 #include "transform_graph/orientation.h"
00011 #include "transform_graph/position.h"
00012 
00013 namespace transform_graph {
00020 class Transform {
00021  public:
00023   Transform();
00024 
00032   Transform(const transform_graph::Position& position,
00033             const transform_graph::Orientation& orientation);
00035   Transform(const tf::Transform& st);
00037   Transform(const geometry_msgs::Pose& p);
00039   Transform(const geometry_msgs::Transform& p);
00041   Transform(const Eigen::Affine3d& a);
00043   Transform(const Eigen::Matrix4d& m);
00044 
00047   static Transform Identity();
00048 
00050   //
00052   transform_graph::Position position() const;
00053 
00055   //
00057   transform_graph::Orientation orientation() const;
00058 
00061   tf::Transform tf_transform() const;
00062 
00065   geometry_msgs::Pose pose() const;
00066 
00069   geometry_msgs::Transform transform() const;
00070 
00073   Eigen::Matrix4d matrix() const;
00074 
00077   Eigen::Affine3d affine() const;
00078 
00082   void ToPose(geometry_msgs::Pose* pose) const;
00083 
00086   transform_graph::Transform inverse() const;
00087 
00088  private:
00089   Eigen::Affine3d transform_;
00090 };
00091 }  // namespace transform_graph
00092 
00093 #endif  // _TRANSFORM_GRAPH_TRANSFORM_H_


transform_graph
Author(s):
autogenerated on Sat Jun 8 2019 19:23:43