00001 #include "transform_graph/graph.h"
00002 
00003 #include <map>
00004 #include <string>
00005 #include <utility>
00006 #include <vector>
00007 
00008 #include "Eigen/Dense"
00009 #include "Eigen/Geometry"
00010 
00011 #include "transform_graph/explicit_types.h"
00012 #include "transform_graph/transform.h"
00013 
00014 using std::pair;
00015 using std::string;
00016 
00017 typedef pair<string, string> FrameKey;
00018 
00019 namespace transform_graph {
00020 Graph::Graph() : transforms_(), graph_() {}
00021 
00022 void Graph::Add(const std::string& name, const RefFrame& source,
00023                 const Transform& transform) {
00024   graph_.AddEdge(source.id(), name);
00025   transforms_[FrameKey(source.id(), name)] = transform;
00026 }
00027 
00028 bool Graph::CanTransform(const string& frame1_id,
00029                          const string& frame2_id) const {
00030   std::vector<string> path;
00031   graph_.Path(frame1_id, frame2_id, &path);
00032   return path.size() > 0;
00033 }
00034 
00035 bool Graph::ComputeDescription(const LocalFrame& local_frame,
00036                                const RefFrame& reference_frame,
00037                                Transform* transform) const {
00038   std::vector<string> path;
00039   graph_.Path(reference_frame.id(), local_frame.id(), &path);
00040 
00041   if (path.size() == 0) {
00042     return false;
00043   }
00044 
00045   Eigen::Affine3d result = Eigen::Affine3d::Identity();
00046   for (size_t i = 1; i < path.size(); ++i) {
00047     Eigen::Affine3d working = Eigen::Affine3d::Identity();
00048     bool success = GetTransform(path[i - 1], path[i], &working);
00049     if (!success) {
00050       return false;
00051     }
00052     result = result * working;
00053   }
00054   *transform = result;
00055 
00056   return true;
00057 }
00058 
00059 bool Graph::ComputeMapping(const From& from, const To& to,
00060                            Transform* transform) const {
00061   return ComputeDescription(to.id(), RefFrame(from.id()), transform);
00062 }
00063 
00064 bool Graph::DescribePose(const Transform& in, const Source& source_frame,
00065                          const Target& target_frame, Transform* out) const {
00066   std::vector<string> path;
00067   graph_.Path(target_frame.id(), source_frame.id(), &path);
00068 
00069   if (path.size() == 0) {
00070     return false;
00071   }
00072 
00073   Eigen::Affine3d result = Eigen::Affine3d::Identity();
00074   for (size_t i = 1; i < path.size(); ++i) {
00075     Eigen::Affine3d working = Eigen::Affine3d::Identity();
00076     bool success = GetTransform(path[i - 1], path[i], &working);
00077     if (!success) {
00078       return false;
00079     }
00080     result = result * working;
00081   }
00082   result = result * in.matrix();
00083   *out = result;
00084 
00085   return true;
00086 }
00087 
00088 bool Graph::MapPose(const Transform& in, const From& from_frame,
00089                     const To& to_frame, Transform* out) const {
00090   return DescribePose(in, Source(to_frame.id()), Target(from_frame.id()), out);
00091 }
00092 
00093 bool Graph::DescribePosition(const Position& in, const Source& local_frame,
00094                              const Target& reference_frame,
00095                              Position* out) const {
00096   std::vector<string> path;
00097   graph_.Path(reference_frame.id(), local_frame.id(), &path);
00098 
00099   if (path.size() == 0) {
00100     return false;
00101   }
00102 
00103   Eigen::Vector3d result = in.vector();
00104   
00105   for (int i = static_cast<int>(path.size()) - 2; i >= 0; --i) {
00106     Eigen::Affine3d working = Eigen::Affine3d::Identity();
00107     bool success = GetTransform(path[i], path[i + 1], &working);
00108     if (!success) {
00109       return false;
00110     }
00111     result = working * result;
00112   }
00113   *out = result;
00114 
00115   return true;
00116 }
00117 
00118 bool Graph::MapPosition(const Position& in, const From& frame_in,
00119                         const To& frame_out, Position* out) const {
00120   return DescribePosition(in, Source(frame_out.id()), Target(frame_in.id()),
00121                           out);
00122 }
00123 
00124 bool Graph::GetTransform(const std::string& source, const std::string& target,
00125                          Eigen::Affine3d* out) const {
00126   FrameKey key(source, target);
00127   FrameKey inverse_key(target, source);
00128   std::map<FrameKey, Transform>::const_iterator it = transforms_.find(key);
00129   if (it != transforms_.end()) {
00130     *out = it->second.matrix();
00131     return true;
00132   } else {
00133     it = transforms_.find(inverse_key);
00134     if (it != transforms_.end()) {
00135       *out = it->second.inverse().matrix();
00136       return true;
00137     }
00138   }
00139   return false;
00140 }
00141 }