00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00039 #include <pose_graph/diff_subscriber.h>
00040 #include <graph_mapping_utils/utils.h>
00041 #include <graph_mapping_msgs/GraphConstraint.h>
00042 #include <graph_mapping_msgs/ConstraintGraphDiff.h>
00043 #include <ros/ros.h>
00044 #include <boost/optional.hpp>
00045
00046 namespace laser_slam
00047 {
00048
00049 namespace pg=pose_graph;
00050 namespace msg=graph_mapping_msgs;
00051 namespace util=graph_mapping_utils;
00052
00053 using std::string;
00054 using boost::optional;
00055
00056 typedef optional<const msg::ConstraintGraphDiff&> OptionalDiff;
00057
00058
00059
00060
00061
00062 class OdomConstraints
00063 {
00064 public:
00065 OdomConstraints (ros::NodeHandle& param_nh);
00066
00067 private:
00068
00069 tf::Pose fixedFramePose (const ros::Time& t);
00070 void diffCB (OptionalDiff diff, const pg::ConstraintGraph& g);
00071
00072
00073
00074
00075
00076 ros::NodeHandle param_nh_;
00077 const string base_frame_;
00078 const string odom_frame_;
00079
00080
00081
00082
00083
00084 optional<unsigned> last_node_;
00085 optional<tf::Pose> last_odom_pose_;
00086
00087
00088
00089
00090
00091 ros::NodeHandle nh_;
00092 tf::TransformListener tf_;
00093 pg::DiffSubscriber diff_sub_;
00094 ros::Publisher constraint_pub_;
00095
00096 };
00097
00098
00099
00100
00101
00102 OdomConstraints::OdomConstraints (ros::NodeHandle& param_nh) :
00103 param_nh_(param_nh),
00104 base_frame_(util::getParam<string>(param_nh_, "base_frame")),
00105 odom_frame_(util::getParam<string>(param_nh_, "fixed_frame")),
00106 diff_sub_(boost::bind(&OdomConstraints::diffCB, this, _1, _2)),
00107 constraint_pub_(nh_.advertise<msg::GraphConstraint>("graph_constraints", 10))
00108 {
00109 ROS_INFO ("odom_constraint_node initialized");
00110 }
00111
00112
00113
00114
00115
00116 tf::Pose OdomConstraints::fixedFramePose (const ros::Time& t)
00117 {
00118 tf_.waitForTransform(odom_frame_, base_frame_, t, ros::Duration(1.0));
00119 tf::StampedTransform tr;
00120 tf_.lookupTransform(odom_frame_, base_frame_, t, tr);
00121 return tr;
00122 }
00123
00124 void OdomConstraints::diffCB (OptionalDiff diff,
00125 const pg::ConstraintGraph& g)
00126 {
00127 if (!diff)
00128 {
00129 ROS_INFO ("Not adding constraint since got full graph rather than a diff");
00130 }
00131 else if (diff->new_nodes.size()!=1)
00132 {
00133 ROS_INFO ("Not adding constraint since diff had %zu new nodes",
00134 diff->new_nodes.size());
00135 }
00136 else
00137 {
00138 const unsigned n=diff->new_nodes[0].id;
00139 try
00140 {
00141 const tf::Pose odom_pose = fixedFramePose(diff->new_node_timestamps[0]);
00142 if (last_node_)
00143 {
00144 msg::GraphConstraint constraint;
00145 constraint.src = *last_node_;
00146 constraint.dest = n;
00147 constraint.constraint.pose =
00148 util::toPose(util::relativePose(odom_pose, *last_odom_pose_));
00149 constraint.constraint.precision =
00150 util::makePrecisionMatrix(1,1,1,1);
00151 constraint_pub_.publish(constraint);
00152 ROS_INFO_STREAM ("Added constraint to " << *last_node_ <<
00153 " given new node " << n <<
00154 " at " << util::toString(odom_pose));
00155 }
00156 else
00157 {
00158 ROS_INFO("First node %u seen ", n);
00159 }
00160
00161 last_node_ = n;
00162 last_odom_pose_ = odom_pose;
00163 ROS_INFO_STREAM ("Last node is now " << *last_node_ << " at "
00164 << util::toString(*last_odom_pose_));
00165 }
00166 catch (tf::TransformException& e)
00167 {
00168 ROS_WARN ("Ignoring new node %u due to tf exception '%s'", n, e.what());
00169 }
00170 }
00171 }
00172
00173
00174 }
00175
00176 int main (int argc, char** argv)
00177 {
00178 ros::init(argc, argv, "odom_constraint_node");
00179 ros::NodeHandle param_nh("laser_slam_node");
00180 laser_slam::OdomConstraints node(param_nh);
00181 ros::spin();
00182 return 0;
00183 }