Go to the documentation of this file.00001 #ifndef _TRANSFORM_GRAPH_GRAPH_H_
00002 #define _TRANSFORM_GRAPH_GRAPH_H_
00003
00004 #include <map>
00005 #include <string>
00006 #include <utility>
00007
00008 #include "Eigen/Dense"
00009 #include "Eigen/Geometry"
00010
00011 #include "transform_graph/explicit_types.h"
00012 #include "transform_graph/graph_internal.h"
00013 #include "transform_graph/transform.h"
00014
00015 namespace transform_graph {
00056 class Graph {
00057 public:
00059 Graph();
00060
00087 void Add(const std::string& name, const RefFrame& ref_frame_name,
00088 const Transform& transform);
00089
00094 bool CanTransform(const std::string& frame1_id,
00095 const std::string& frame2_id) const;
00096
00136 bool ComputeDescription(const LocalFrame& local, const RefFrame& reference,
00137 Transform* transform) const;
00138
00169 bool ComputeMapping(const From& from, const To& to,
00170 Transform* transform) const;
00171
00203 bool DescribePose(const Transform& in, const Source& source_frame,
00204 const Target& target_frame, Transform* out) const;
00205
00223 bool MapPose(const Transform& in, const From& frame_in, const To& frame_out,
00224 Transform* out) const;
00225
00248 bool DescribePosition(const Position& in, const Source& source_frame,
00249 const Target& target_frame, Position* out) const;
00250
00280 bool MapPosition(const Position& in, const From& frame_in,
00281 const To& frame_out, Position* out) const;
00282
00283 private:
00284 bool GetTransform(const std::string& source, const std::string& target,
00285 Eigen::Affine3d* out) const;
00286
00287 std::map<std::pair<std::string, std::string>, Transform> transforms_;
00288 internal::Graph graph_;
00289 };
00290 }
00291
00292 #endif // _TRANSFORM_GRAPH_GRAPH_H_