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
00031 #include <laser_slam/point_cloud_snapshotter.h>
00032 #include <graph_slam/graph_mapper.h>
00033 #include <graph_mapping_utils/ros.h>
00034 #include <graph_mapping_utils/geometry.h>
00035 #include <graph_mapping_utils/msg.h>
00036 #include <tf/transform_broadcaster.h>
00037 #include <boost/thread.hpp>
00038
00039 namespace util=graph_mapping_utils;
00040 namespace msg=graph_mapping_msgs;
00041 namespace gm=geometry_msgs;
00042 namespace pg=pose_graph;
00043
00044 using std::string;
00045 typedef boost::shared_ptr<tf::TransformListener> TfPtr;
00046 typedef msg::ConstraintGraphDiff::ConstPtr DiffPtr;
00047 typedef boost::mutex::scoped_lock Lock;
00048
00049 namespace laser_slam
00050 {
00051
00053 class OdomSlam
00054 {
00055 public:
00056 OdomSlam (TfPtr tf);
00057
00058 private:
00059
00060 void diffCallback (DiffPtr diff);
00061 void updateLocalization (const ros::TimerEvent& e);
00062
00063 ros::NodeHandle param_nh_;
00064 const string fixed_frame_, opt_frame_, base_frame_;
00065 TfPtr tf_;
00066 warehouse::WarehouseClient db_;
00067 pg::CachedNodeMap<gm::Pose> ff_poses_;
00068
00069 boost::optional<unsigned> last_node_;
00070 tf::Pose last_pose_;
00071 ros::Time last_node_stamp_;
00072
00073 boost::mutex mutex_;
00074 ros::NodeHandle nh_;
00075 ros::Publisher constraint_pub_, loc_pub_;
00076 ros::Subscriber diff_sub_;
00077 ros::Timer loc_timer_;
00078 };
00079
00080
00081 OdomSlam::OdomSlam (TfPtr tf) :
00082 param_nh_("~"), fixed_frame_(util::getParam<string>(param_nh_, "fixed_frame")),
00083 opt_frame_(util::getParam<string>(param_nh_, "optimization_frame")),
00084 base_frame_(util::getParam<string>(param_nh_, "base_frame")), tf_(tf),
00085 db_("graph_mapping"), ff_poses_(&db_, "fixed_frame_poses"),
00086 constraint_pub_(nh_.advertise<msg::GraphConstraint>("graph_constraints", 10)),
00087 loc_pub_(nh_.advertise<msg::LocalizationDistribution> ("graph_localization", 5)),
00088 diff_sub_(nh_.subscribe("graph_diffs", 100, &OdomSlam::diffCallback, this)),
00089 loc_timer_(nh_.createTimer(util::duration(util::getParam<double>(param_nh_, "localization_rate", 5.0)),
00090 &OdomSlam::updateLocalization, this))
00091 {
00092 last_node_ = 1;
00093 last_pose_.setIdentity();
00094 last_node_stamp_ = ros::Time::now();
00095 }
00096
00097 void OdomSlam::diffCallback (DiffPtr diff)
00098 {
00099 Lock l(mutex_);
00100 if (diff->new_nodes.size() == 1) {
00101 const unsigned n(diff->new_nodes[0].id);
00102 tf::Pose pose;
00103 while (true) {
00104 try {
00105 pose = util::toPose(*ff_poses_.get(n));
00106 break;
00107 }
00108 catch (pg::DataNotFoundException& e) {
00109 ROS_INFO_STREAM ("Still waiting for fixed frame pose");
00110 ros::Duration(0.2).sleep();
00111 }
00112 }
00113 if (last_node_) {
00114 msg::GraphConstraint::Ptr constraint(new msg::GraphConstraint());
00115 constraint->src = *last_node_;
00116 constraint->dest = n;
00117 constraint->constraint.pose = util::toPose(util::relativePose(pose, last_pose_));
00118 constraint->constraint.precision = util::makePrecisionMatrix(1, 1, 1, 1);
00119 constraint_pub_.publish(constraint);
00120 }
00121 last_node_ = n;
00122 last_pose_ = pose;
00123 last_node_stamp_ = diff->new_node_timestamps[0];
00124 }
00125 }
00126
00127 void OdomSlam::updateLocalization (const ros::TimerEvent& e)
00128 {
00129 Lock lock(mutex_);
00130 if (last_node_) {
00131 msg::LocalizationDistribution::Ptr d(new msg::LocalizationDistribution());
00132 d->stamp = ros::Time::now();
00133 gm::PoseStamped id;
00134 id.pose.orientation.w = 1.0;
00135 id.header.stamp = d->stamp;
00136 id.header.frame_id = base_frame_;
00137 try {
00138 tf_->waitForTransform(fixed_frame_, base_frame_, d->stamp, ros::Duration(0.2));
00139 gm::PoseStamped fixed_frame_pose;
00140 tf_->transformPose(fixed_frame_, id, fixed_frame_pose);
00141 tf::Pose ff_pose = util::toPose(fixed_frame_pose.pose);
00142 d->samples.resize(1);
00143 d->samples[0].header.frame_id = util::nodeFrame(*last_node_);
00144 d->samples[0].pose = util::toPose(util::relativePose(ff_pose, last_pose_));
00145 loc_pub_.publish(d);
00146 }
00147 catch (tf::TransformException& e) {
00148 ROS_WARN_STREAM ("Skipping localization due to tf exception: " << e.what());
00149 }
00150 }
00151 else
00152 ROS_DEBUG_STREAM_NAMED ("localization", "Not updating localization because have no last node");
00153 }
00154
00155
00156 }
00157
00158 int main (int argc, char** argv)
00159 {
00160 ros::init(argc, argv, "odom_slam_node");
00161
00162
00163 ros::AsyncSpinner spinner(3);
00164 spinner.start();
00165
00166 TfPtr tf(new tf::TransformListener());
00167
00168
00169 graph_slam::GraphMapper node;
00170
00171
00172 laser_slam::PointCloudSnapshotter snapshotter(tf, ros::NodeHandle("~"));
00173
00174
00175 laser_slam::OdomSlam odom_slam(tf);
00176
00177 ros::spin();
00178 return 0;
00179 }