spa_conversion.cpp
Go to the documentation of this file.
00001 #include <pose_graph/spa_conversion.h>
00002 #include <pose_graph/transforms.h>
00003 #include <pose_graph/utils.h>
00004 #include <tf/transform_datatypes.h>
00005 #include <boost/foreach.hpp>
00006 #include <boost/tuple/tuple.hpp>
00007 #include <set>
00008 
00009 namespace pose_graph
00010 {
00011 
00012 using std::set;
00013 using boost::tie;
00014 using sba::Node;
00015 using sba::SysSPA;
00016 using sba::ConP2;
00017 using geometry_msgs::Pose;
00018 
00019 // Make a spa node given an initial pose estimate
00020 Node makeNode (const Pose& initial_pose)
00021 {
00022   Node n;
00023   n.trans = translationToVector4d(initial_pose.position);
00024   n.qrot = quaternionMsgToVector4d(initial_pose.orientation);
00025   n.normRot();
00026   n.setTransform();
00027   n.setDr();
00028   return n;
00029 }
00030 
00031 
00032 // Turn a PoseConstraint into a ConP2
00033 // Currently ignores precision
00034 ConP2 makeSpaConstraint (const PoseConstraint& constraint)
00035 {
00036   ConP2 spa;
00037   spa.tmean = constraint.translation;
00038   spa.qpmean = constraint.rotation.inverse();
00039 
00040   // Todo: set precision correctly based on constraint precision
00041   spa.prec.setIdentity();
00042 
00043   return spa;
00044 }
00045 
00046 
00047 // Turn a pose graph into a SysSpa
00048 SpaConversionResult poseGraphToSpa (const PoseGraph& pose_graph)
00049 {
00050   SpaPtr spa(new SysSPA());
00051   map<NodeId, unsigned> node_indices;
00052   unsigned next_index=0;
00053 
00054   // 1. Add the nodes
00055   BOOST_FOREACH (const NodeId n, pose_graph.allNodes()) {
00056     spa->nodes.push_back(makeNode(pose_graph.getInitialPoseEstimate(n)));
00057     node_indices[n] = next_index++;
00058   }
00059 
00060   // 2. Add the edge constraints
00061   BOOST_FOREACH (const EdgeId e, pose_graph.allEdges()) {
00062     
00063     NodeId from, to;
00064     tie(from, to) = pose_graph.incidentNodes(e);
00065     const pose_graph::PoseConstraint constraint = pose_graph.getConstraint(e);
00066     ConP2 spa_constraint = makeSpaConstraint(constraint);
00067 
00068     spa_constraint.ndr = node_indices[from];
00069     spa_constraint.nd1 = node_indices[to];
00070     spa->p2cons.push_back(spa_constraint);
00071     ROS_DEBUG_STREAM_NAMED ("pose_graph_spa", "Adding constraint with tmean " << spa_constraint.tmean << 
00072                             " and qpmean " << spa_constraint.qpmean.coeffs() << " from " << 
00073                             spa_constraint.ndr << " to " << spa_constraint.nd1);
00074   }
00075 
00076   return SpaConversionResult(spa, node_indices);
00077 }
00078 
00079 
00080 // Return the Pose corresponding to a spa node
00081 Pose getNodePose (const sba::Node& n)
00082 {
00083   Pose pose;
00084 
00085   pose.position.x = n.trans(0);
00086   pose.position.y = n.trans(1);
00087   pose.position.z = n.trans(2);
00088 
00089   // Per documentation, qrot is in xyzw order
00090   // Since Eigen uses wxyz, n.qrot(w) is not the same as n.qrot[3]
00091   pose.orientation.x = n.qrot.x();
00092   pose.orientation.y = n.qrot.y();
00093   pose.orientation.z = n.qrot.z();
00094   pose.orientation.w = n.qrot.w();
00095 
00096   return pose;
00097 }
00098 
00099 
00100 // Convert and optimize a graph
00101 NodePoseMap optimizeGraph (const PoseGraph& g)
00102 {
00103   /******************************
00104    * 1. Convert graph to SPA
00105    ******************************/
00106 
00107   ROS_DEBUG_NAMED ("pose_graph_spa", "Converting graph with %zu nodes to spa", g.allNodes().size());
00108   SpaConversionResult res=poseGraphToSpa(g);
00109 
00110   /******************************
00111    * 2. Optimize
00112    ******************************/
00113 
00114   const size_t num_nodes = res.spa->nodes.size();
00115   const size_t num_constraints = res.spa->p2cons.size();
00116 
00117   // Shouldn't need this check, but spa dies otherwise
00118   if (num_nodes>=2 && num_constraints>=1) { 
00119     ROS_DEBUG_NAMED ("pose_graph_spa", "Performing spa with %zu nodes and %zu constraints",
00120                      num_nodes, num_constraints);
00121     res.spa->doSPA(10, 1.0e-4, true);
00122     ROS_DEBUG_NAMED ("pose_graph_spa", "Graph optimization complete");
00123   }
00124   else 
00125     ROS_DEBUG_NAMED ("pose_graph_spa", "Not optimizing graph with %zu nodes and %zu constraints",
00126                      num_nodes, num_constraints);
00127   
00128   /******************************
00129    * 3. Return optimized poses
00130    ******************************/
00131 
00132   NodePoseMap optimized_poses;
00133   BOOST_FOREACH (const NodeIndexMap::value_type entry, res.node_index_map) 
00134     optimized_poses[entry.first] = getNodePose(res.spa->nodes[entry.second]);
00135   return optimized_poses;
00136 }
00137 
00138 
00139 
00140 
00141 
00142 } // namespace


pose_graph
Author(s): Bhaskara Marthi
autogenerated on Tue Jan 7 2014 11:17:15