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 #include "mrpt_localization_node.h"
00030 #include <boost/interprocess/sync/scoped_lock.hpp>
00031 #include <geometry_msgs/PoseArray.h>
00032
00033 #include <mrpt_bridge/pose.h>
00034 #include <mrpt_bridge/laser_scan.h>
00035 #include <mrpt_bridge/time.h>
00036 #include <mrpt_bridge/map.h>
00037 #include <mrpt/base.h>
00038 #include <mrpt/slam.h>
00039 #include <mrpt/gui.h>
00040
00041 int main(int argc, char **argv) {
00042
00043 ros::init(argc, argv, "localization");
00044 ros::NodeHandle n;
00045 PFLocalizationNode my_node(n);
00046 my_node.init();
00047 my_node.loop();
00048 return 0;
00049 }
00050
00051 PFLocalizationNode::~PFLocalizationNode() {
00052 }
00053
00054 PFLocalizationNode::PFLocalizationNode(ros::NodeHandle &n) :
00055 PFLocalization(new PFLocalizationNode::Parameters(&odom_params_)), n_(n), loop_count_(0) {
00056 }
00057
00058 PFLocalizationNode::Parameters *PFLocalizationNode::param() {
00059 return (PFLocalizationNode::Parameters*) param_;
00060 }
00061
00062 void PFLocalizationNode::init() {
00063 PFLocalization::init();
00064 subLaser0_ = n_.subscribe("scan", 1, &PFLocalizationNode::callbackLaser, this);
00065 subLaser1_ = n_.subscribe("scan1", 1, &PFLocalizationNode::callbackLaser, this);
00066 subLaser2_ = n_.subscribe("scan2", 1, &PFLocalizationNode::callbackLaser, this);
00067
00068 subLaser2_ = n_.subscribe("initialpose", 1, &PFLocalizationNode::callbackInitialpose, this);
00069
00070 if(!param()->mapFile.empty()) {
00071 mrpt_bridge::convert(*metric_map_.m_gridMaps[0], resp_.map);
00072 pub_map_ = n_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00073 pub_metadata_= n_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
00074 service_map_ = n_.advertiseService("static_map", &PFLocalizationNode::mapCallback, this);
00075 }
00076 pub_Particles_ = n_.advertise<geometry_msgs::PoseArray>("particlecloud", 1, true);
00077 }
00078
00079 void PFLocalizationNode::loop() {
00080 ROS_INFO("loop");
00081 for (ros::Rate rate(param()->rate); ros::ok(); loop_count_++) {
00082 param()->update(loop_count_);
00083 if(loop_count_%param()->map_update_skip == 0) publishMap();
00084 if(loop_count_%param()->particlecloud_update_skip == 0) publishParticles();
00085 publishTF();
00086 ros::spinOnce();
00087 rate.sleep();
00088 }
00089 }
00090
00091 bool PFLocalizationNode::waitForTransform(mrpt::poses::CPose3D &des, const std::string& target_frame, const std::string& source_frame, const ros::Time& time, const ros::Duration& timeout, const ros::Duration& polling_sleep_duration){
00092 tf::StampedTransform transform;
00093 try
00094 {
00095 listenerTF_.waitForTransform(target_frame, source_frame, time, polling_sleep_duration);
00096 listenerTF_.lookupTransform(target_frame, source_frame, time, transform);
00097 }
00098 catch(tf::TransformException)
00099 {
00100 ROS_INFO("Failed to get transform target_frame (%s) to source_frame (%s)", target_frame.c_str(), source_frame.c_str());
00101 return false;
00102 }
00103 mrpt_bridge::convert(transform, des);
00104 return true;
00105 }
00106
00107
00108 void PFLocalizationNode::callbackLaser (const sensor_msgs::LaserScan &_msg) {
00109
00110 mrpt::slam::CObservation2DRangeScanPtr laser = mrpt::slam::CObservation2DRangeScan::Create();
00111
00112
00113 if(laser_poses_.find(_msg.header.frame_id) == laser_poses_.end()) {
00114 updateLaserPose (_msg.header.frame_id);
00115 } else {
00116
00117
00118 mrpt_bridge::convert(_msg, laser_poses_[_msg.header.frame_id], *laser);
00119
00120
00121 std::string base_frame_id = tf::resolve(param()->tf_prefix, param()->base_frame_id);
00122 std::string odom_frame_id = tf::resolve(param()->tf_prefix, param()->odom_frame_id);
00123 mrpt::slam::CObservationOdometryPtr odometry;
00124 mrpt::poses::CPose3D poseOdom;
00125 if(this->waitForTransform(poseOdom, odom_frame_id, base_frame_id, _msg.header.stamp, ros::Duration(1))){
00126 odometry = mrpt::slam::CObservationOdometry::Create();
00127 odometry->sensorLabel = odom_frame_id;
00128 odometry->hasEncodersInfo = false;
00129 odometry->hasVelocities = false;
00130 odometry->odometry.x() = poseOdom.x();
00131 odometry->odometry.y() = poseOdom.y();
00132 odometry->odometry.phi() = poseOdom.yaw();
00133 }
00134 mrpt::slam::CSensoryFramePtr sf = mrpt::slam::CSensoryFrame::Create();
00135 mrpt::slam::CObservationPtr obs = mrpt::slam::CObservationPtr(laser);
00136 sf->insert(obs);
00137 observation(sf, odometry);
00138 if(param()->gui_mrpt) show3DDebug(sf);
00139 }
00140 }
00141
00142 bool PFLocalizationNode::waitForMap() {
00143 clientMap_ = n_.serviceClient<nav_msgs::GetMap>("static_map");
00144 nav_msgs::GetMap srv;
00145 while (!clientMap_.call(srv) && ros::ok()) {
00146 ROS_INFO("waiting for map service!");
00147 sleep(1);
00148 }
00149 updateMap (srv.response.map);
00150 clientMap_.shutdown();
00151 }
00152
00153 void PFLocalizationNode::updateLaserPose (std::string _frame_id) {
00154 mrpt::poses::CPose3D pose;
00155 tf::StampedTransform transform;
00156 try {
00157 listenerTF_.lookupTransform(param()->base_frame_id, _frame_id, ros::Time(0), transform);
00158 tf::Vector3 translation = transform.getOrigin();
00159 tf::Quaternion quat = transform.getRotation();
00160 pose.x() = translation.x();
00161 pose.y() = translation.y();
00162 pose.z() = translation.z();
00163 double roll, pitch, yaw;
00164 tf::Matrix3x3 Rsrc(quat);
00165 mrpt::poses::CMatrixDouble33 Rdes;
00166 for(int c = 0; c < 3; c++)
00167 for(int r = 0; r < 3; r++)
00168 Rdes(r,c) = Rsrc.getRow(r)[c];
00169 pose.setRotationMatrix(Rdes);
00170 laser_poses_[_frame_id] = pose;
00171 }
00172 catch (tf::TransformException ex) {
00173 ROS_ERROR("%s",ex.what());
00174 ros::Duration(1.0).sleep();
00175 }
00176
00177 }
00178
00179 void PFLocalizationNode::callbackInitialpose (const geometry_msgs::PoseWithCovarianceStamped& _msg) {
00180 const geometry_msgs::PoseWithCovariance &pose = _msg.pose;
00181 mrpt_bridge::convert(pose, initialPose_);
00182 log_info("callbackInitialpose");
00183 state_ = INIT;
00184 }
00185
00186 void PFLocalizationNode::updateMap (const nav_msgs::OccupancyGrid &_msg) {
00187 ASSERT_( metric_map_.m_gridMaps.size()==1 );
00188 mrpt_bridge::convert(_msg, *metric_map_.m_gridMaps[0]);
00189 }
00190
00191 bool PFLocalizationNode::mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res )
00192 {
00193 ROS_INFO("mapCallback: service requested!\n");
00194 res = resp_;
00195 return true;
00196 }
00197
00198 void PFLocalizationNode::publishMap () {
00199 resp_.map.header.stamp = ros::Time::now();
00200 resp_.map.header.frame_id = param()->global_frame_id;
00201 resp_.map.header.seq = loop_count_;
00202 if(pub_map_.getNumSubscribers() > 0) {
00203 pub_map_.publish(resp_.map );
00204 }
00205 if(pub_metadata_.getNumSubscribers() > 0) {
00206 pub_metadata_.publish( resp_.map.info );
00207 }
00208 }
00209
00210 void PFLocalizationNode::publishParticles () {
00211 geometry_msgs::PoseArray poseArray;
00212 std::string global_frame = param()->global_frame_id;
00213 poseArray.header.frame_id = global_frame;
00214 poseArray.header.stamp = ros::Time::now();
00215 poseArray.header.seq = loop_count_;
00216 poseArray.poses.resize(pdf_.particlesCount());
00217 for(size_t i = 0; i < pdf_.particlesCount(); i++) {
00218 mrpt::poses::CPose2D p = pdf_.getParticlePose(i);
00219 mrpt_bridge::convert(p, poseArray.poses[i]);
00220 }
00221 mrpt::poses::CPose2D p;
00222 pub_Particles_.publish(poseArray);
00223 }
00224
00225 void PFLocalizationNode::publishTF() {
00226
00227
00228 mrpt::poses::CPose2D robotPose;
00229 pdf_.getMean(robotPose);
00230 std::string base_frame_id = tf::resolve(param()->tf_prefix, param()->base_frame_id);
00231 std::string global_frame_id = tf::resolve(param()->tf_prefix, param()->global_frame_id);
00232 std::string odom_frame_id = tf::resolve(param()->tf_prefix, param()->odom_frame_id);
00233 tf::Stamped<tf::Pose> odom_to_map;
00234 tf::Transform tmp_tf;
00235 ros::Time stamp;
00236 mrpt_bridge::convert(timeLastUpdate_, stamp);
00237 mrpt_bridge::convert(robotPose, tmp_tf);
00238 try
00239 {
00240 tf::Stamped<tf::Pose> tmp_tf_stamped (tmp_tf.inverse(), stamp, base_frame_id);
00241
00242 listenerTF_.transformPose(odom_frame_id, tmp_tf_stamped, odom_to_map);
00243 }
00244 catch(tf::TransformException)
00245 {
00246 ROS_INFO("Failed to subtract global_frame (%s) form odom_frame (%s)", global_frame_id.c_str(), odom_frame_id.c_str());
00247 return;
00248 }
00249
00250 tf::Transform latest_tf_ = tf::Transform(tf::Quaternion(odom_to_map.getRotation()),
00251 tf::Point(odom_to_map.getOrigin()));
00252
00253
00254
00255 ros::Duration transform_tolerance_(0.5);
00256 ros::Time transform_expiration = (stamp + transform_tolerance_);
00257 tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(),
00258 transform_expiration,
00259 global_frame_id, odom_frame_id);
00260 tf_broadcaster_.sendTransform(tmp_tf_stamped);
00261
00262 }