00001
00002 #include <ndt_fuser_hmt.h>
00003 #include <ros/ros.h>
00004
00005 #include "pcl/point_cloud.h"
00006 #include "sensor_msgs/PointCloud2.h"
00007 #include "pcl/io/pcd_io.h"
00008 #include <cstdio>
00009 #include <Eigen/Eigen>
00010 #include <fstream>
00011 #include "message_filters/subscriber.h"
00012 #include "tf/message_filter.h"
00013 #include <tf/transform_broadcaster.h>
00014 #include <tf_conversions/tf_eigen.h>
00015 #include <boost/circular_buffer.hpp>
00016 #include <laser_geometry/laser_geometry.h>
00017 #include <nav_msgs/Odometry.h>
00018 #include <geometry_msgs/PoseStamped.h>
00019
00020 #include <message_filters/subscriber.h>
00021 #include <message_filters/synchronizer.h>
00022 #include <message_filters/sync_policies/approximate_time.h>
00023 #include <std_srvs/Empty.h>
00024
00025 #ifndef SYNC_FRAMES
00026 #define SYNC_FRAMES 20
00027 #endif
00028
00032 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::LaserScan, nav_msgs::Odometry> LaserOdomSync;
00033 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::LaserScan, geometry_msgs::PoseStamped> LaserPoseSync;
00034 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, nav_msgs::Odometry> PointsOdomSync;
00035 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, geometry_msgs::PoseStamped> PointsPoseSync;
00036
00037 class NDTFuserNode {
00038
00039 protected:
00040
00041 ros::NodeHandle nh_;
00042
00043 message_filters::Subscriber<sensor_msgs::PointCloud2> *points2_sub_;
00044 message_filters::Subscriber<sensor_msgs::LaserScan> *laser_sub_;
00045 message_filters::Subscriber<nav_msgs::Odometry> *odom_sub_;
00046
00047
00048 tf::TransformBroadcaster tf_;
00049 ros::Publisher output_pub_;
00050 Eigen::Affine3d pose_, T, sensor_pose_;
00051
00052 unsigned int nb_added_clouds_;
00053 double varz;
00054
00055 boost::mutex m, message_m;
00056 lslgeneric::NDTFuserHMT<pcl::PointXYZ> *fuser;
00057 std::string points_topic, laser_topic, map_dir, map_name, odometry_topic;
00058 double size_x, size_y, size_z, resolution, sensor_range, min_laser_range_;
00059 bool visualize, match2D, matchLaser, beHMT, useOdometry;
00060
00061 double pose_init_x,pose_init_y,pose_init_z,
00062 pose_init_r,pose_init_p,pose_init_t;
00063 double sensor_pose_x,sensor_pose_y,sensor_pose_z,
00064 sensor_pose_r,sensor_pose_p,sensor_pose_t;
00065 laser_geometry::LaserProjection projector_;
00066
00067 message_filters::Synchronizer< LaserOdomSync > *sync_lo_;
00068 message_filters::Synchronizer< LaserPoseSync > *sync_lp_;
00069
00070 message_filters::Synchronizer< PointsOdomSync > *sync_po_;
00071 message_filters::Synchronizer< PointsPoseSync > *sync_pp_;
00072 ros::ServiceServer save_map_;
00073
00074 Eigen::Affine3d last_odom, this_odom;
00075 public:
00076
00077 NDTFuserNode(ros::NodeHandle param_nh) : nb_added_clouds_(0)
00078 {
00080 param_nh.param<std::string>("points_topic",points_topic,"points");
00082 param_nh.param<std::string>("laser_topic",laser_topic,"laser_scan");
00083
00087 param_nh.param<std::string>("map_directory",map_dir,"map");
00088 param_nh.param<std::string>("map_name_prefix",map_name,"");
00089
00091 param_nh.param("pose_init_x",pose_init_x,0.);
00092 param_nh.param("pose_init_y",pose_init_y,0.);
00093 param_nh.param("pose_init_z",pose_init_z,0.);
00094 param_nh.param("pose_init_r",pose_init_r,0.);
00095 param_nh.param("pose_init_p",pose_init_p,0.);
00096 param_nh.param("pose_init_t",pose_init_t,0.);
00097
00099 param_nh.param("sensor_pose_x",sensor_pose_x,0.);
00100 param_nh.param("sensor_pose_y",sensor_pose_y,0.);
00101 param_nh.param("sensor_pose_z",sensor_pose_z,0.);
00102 param_nh.param("sensor_pose_r",sensor_pose_r,0.);
00103 param_nh.param("sensor_pose_p",sensor_pose_p,0.);
00104 param_nh.param("sensor_pose_t",sensor_pose_t,0.);
00105
00107 param_nh.param("size_x_meters",size_x,10.);
00108 param_nh.param("size_y_meters",size_y,10.);
00109 param_nh.param("size_z_meters",size_z,10.);
00110
00112 param_nh.param("sensor_range",sensor_range,3.);
00114 param_nh.param("min_laser_range",min_laser_range_,0.1);
00115
00116
00117 param_nh.param("resolution",resolution,0.10);
00118 param_nh.param("laser_variance_z",varz,resolution/4);
00119
00121 param_nh.param("visualize",visualize,true);
00123 param_nh.param("match2D",match2D,false);
00125 param_nh.param("beHMT",beHMT,false);
00127 param_nh.param("useOdometry",useOdometry,false);
00129 param_nh.param<std::string>("odometry_topic",odometry_topic,"odometry");
00130
00132 param_nh.param("matchLaser",matchLaser,false);
00133
00134 pose_ = Eigen::Translation<double,3>(pose_init_x,pose_init_y,pose_init_z)*
00135 Eigen::AngleAxis<double>(pose_init_r,Eigen::Vector3d::UnitX()) *
00136 Eigen::AngleAxis<double>(pose_init_p,Eigen::Vector3d::UnitY()) *
00137 Eigen::AngleAxis<double>(pose_init_t,Eigen::Vector3d::UnitZ()) ;
00138
00139 sensor_pose_ = Eigen::Translation<double,3>(sensor_pose_x,sensor_pose_y,sensor_pose_z)*
00140 Eigen::AngleAxis<double>(sensor_pose_r,Eigen::Vector3d::UnitX()) *
00141 Eigen::AngleAxis<double>(sensor_pose_p,Eigen::Vector3d::UnitY()) *
00142 Eigen::AngleAxis<double>(sensor_pose_t,Eigen::Vector3d::UnitZ()) ;
00143
00144 if(matchLaser) match2D=true;
00145 fuser = new lslgeneric::NDTFuserHMT<pcl::PointXYZ>(resolution,size_x,size_y,size_z,
00146 sensor_range, visualize,match2D, false, false, 30, map_name, beHMT, map_dir, true);
00147
00148 fuser->setSensorPose(sensor_pose_);
00149
00150 if(!matchLaser) {
00151 points2_sub_ = new message_filters::Subscriber<sensor_msgs::PointCloud2>(nh_,points_topic,1);
00152 if(useOdometry) {
00153 odom_sub_ = new message_filters::Subscriber<nav_msgs::Odometry>(nh_,odometry_topic,10);
00154 sync_po_ = new message_filters::Synchronizer< PointsOdomSync >(PointsOdomSync(SYNC_FRAMES), *points2_sub_, *odom_sub_);
00155 sync_po_->registerCallback(boost::bind(&NDTFuserNode::points2OdomCallback, this, _1, _2));
00156 } else {
00157 points2_sub_->registerCallback(boost::bind( &NDTFuserNode::points2Callback, this, _1));
00158 }
00159 } else {
00160 laser_sub_ = new message_filters::Subscriber<sensor_msgs::LaserScan>(nh_,laser_topic,2);
00161 if(useOdometry) {
00162 odom_sub_ = new message_filters::Subscriber<nav_msgs::Odometry>(nh_,odometry_topic,10);
00163 sync_lo_ = new message_filters::Synchronizer< LaserOdomSync >(LaserOdomSync(SYNC_FRAMES), *laser_sub_, *odom_sub_);
00164 sync_lo_->registerCallback(boost::bind(&NDTFuserNode::laserOdomCallback, this, _1, _2));
00165
00166 } else {
00167 laser_sub_->registerCallback(boost::bind( &NDTFuserNode::laserCallback, this, _1));
00168 }
00169 }
00170 save_map_ = param_nh.advertiseService("save_map", &NDTFuserNode::save_map_callback, this);
00171
00172 }
00173
00174 ~NDTFuserNode()
00175 {
00176 delete fuser;
00177 }
00178
00179 void processFrame(pcl::PointCloud<pcl::PointXYZ> &cloud,
00180 Eigen::Affine3d Tmotion) {
00181
00182 m.lock();
00183 if (nb_added_clouds_ == 0)
00184 {
00185 nb_added_clouds_++;
00186 fuser->initialize(pose_,cloud);
00187 } else {
00188 nb_added_clouds_++;
00189 pose_ = fuser->update(Tmotion,cloud);
00190 }
00191 m.unlock();
00192
00193 tf::Transform transform;
00194 #if ROS_VERSION_MINIMUM(1,9,0)
00195
00196 tf::transformEigenToTF(pose_, transform);
00197 #else
00198
00199 tf::TransformEigenToTF(pose_, transform);
00200 #endif
00201 tf_.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "world", "test"));
00202
00203 }
00204
00205 bool save_map_callback(std_srvs::Empty::Request &req,
00206 std_srvs::Empty::Response &res ) {
00207
00208 bool ret = false;
00209 ROS_INFO("Saving current map to map directory %s", map_dir.c_str());
00210 m.lock();
00211 ret = fuser->saveMap();
00212 m.unlock();
00213
00214 return ret;
00215 }
00216
00217
00218
00219 void points2Callback(const sensor_msgs::PointCloud2::ConstPtr& msg_in)
00220 {
00221 pcl::PointCloud<pcl::PointXYZ> cloud;
00222 message_m.lock();
00223 pcl::fromROSMsg (*msg_in, cloud);
00224 message_m.unlock();
00225 T.setIdentity();
00226 this->processFrame(cloud,T);
00227
00228 };
00229
00230
00231 void points2OdomCallback(const sensor_msgs::PointCloud2::ConstPtr& msg_in,
00232 const nav_msgs::Odometry::ConstPtr& odo_in)
00233 {
00234 Eigen::Quaterniond qd;
00235 Eigen::Affine3d Tm;
00236 pcl::PointCloud<pcl::PointXYZ> cloud;
00237
00238 message_m.lock();
00239 qd.x() = odo_in->pose.pose.orientation.x;
00240 qd.y() = odo_in->pose.pose.orientation.y;
00241 qd.z() = odo_in->pose.pose.orientation.z;
00242 qd.w() = odo_in->pose.pose.orientation.w;
00243
00244 this_odom = Eigen::Translation3d (odo_in->pose.pose.position.x,
00245 odo_in->pose.pose.position.y,odo_in->pose.pose.position.z) * qd;
00246 if (nb_added_clouds_ == 0)
00247 {
00248 Tm.setIdentity();
00249 } else {
00250 Tm = last_odom.inverse()*this_odom;
00251
00252
00253
00254
00255
00256 }
00257 last_odom = this_odom;
00258
00259 pcl::fromROSMsg (*msg_in, cloud);
00260 message_m.unlock();
00261
00262 this->processFrame(cloud,Tm);
00263
00264 };
00265
00266
00267 void laserCallback(const sensor_msgs::LaserScan::ConstPtr& msg_in)
00268 {
00269
00270 sensor_msgs::PointCloud2 cloud;
00271 pcl::PointCloud<pcl::PointXYZ> pcl_cloud_unfiltered, pcl_cloud;
00272 message_m.lock();
00273 projector_.projectLaser(*msg_in, cloud);
00274 message_m.unlock();
00275 pcl::fromROSMsg (cloud, pcl_cloud_unfiltered);
00276
00277 pcl::PointXYZ pt;
00278
00279 for(int i=0; i<pcl_cloud_unfiltered.points.size(); i++) {
00280 pt = pcl_cloud_unfiltered.points[i];
00281 if(sqrt(pt.x*pt.x+pt.y*pt.y) > min_laser_range_) {
00282 pt.z += varz*((double)rand())/(double)INT_MAX;
00283 pcl_cloud.points.push_back(pt);
00284 }
00285 }
00286 ROS_INFO("Got laser points");
00287
00288 T.setIdentity();
00289 this->processFrame(pcl_cloud,T);
00290
00291 };
00292
00293
00294 void laserOdomCallback(const sensor_msgs::LaserScan::ConstPtr& msg_in,
00295 const nav_msgs::Odometry::ConstPtr& odo_in)
00296 {
00297 Eigen::Quaterniond qd;
00298 sensor_msgs::PointCloud2 cloud;
00299 pcl::PointCloud<pcl::PointXYZ> pcl_cloud, pcl_cloud_unfiltered;
00300 Eigen::Affine3d Tm;
00301
00302 message_m.lock();
00303 qd.x() = odo_in->pose.pose.orientation.x;
00304 qd.y() = odo_in->pose.pose.orientation.y;
00305 qd.z() = odo_in->pose.pose.orientation.z;
00306 qd.w() = odo_in->pose.pose.orientation.w;
00307
00308 this_odom = Eigen::Translation3d (odo_in->pose.pose.position.x,
00309 odo_in->pose.pose.position.y,odo_in->pose.pose.position.z) * qd;
00310
00311
00312
00313 if (nb_added_clouds_ == 0)
00314 {
00315 Tm.setIdentity();
00316 } else {
00317 Tm = last_odom.inverse()*this_odom;
00318
00319
00320
00321
00322
00323 }
00324 last_odom = this_odom;
00325
00326 projector_.projectLaser(*msg_in, cloud);
00327 message_m.unlock();
00328
00329 pcl::fromROSMsg (cloud, pcl_cloud_unfiltered);
00330
00331 pcl::PointXYZ pt;
00332
00333 for(int i=0; i<pcl_cloud_unfiltered.points.size(); i++) {
00334 pt = pcl_cloud_unfiltered.points[i];
00335 if(sqrt(pt.x*pt.x+pt.y*pt.y) > min_laser_range_) {
00336 pt.z += varz*((double)rand())/(double)INT_MAX;
00337 pcl_cloud.points.push_back(pt);
00338 }
00339 }
00340 ROS_INFO("Got laser and odometry!");
00341
00342 this->processFrame(pcl_cloud,Tm);
00343
00344 };
00345 public:
00346 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00347 };
00348
00349 int main(int argc, char **argv)
00350 {
00351 ros::init(argc, argv, "ndt_fuser_node");
00352
00353 ros::NodeHandle param("~");
00354 NDTFuserNode t(param);
00355 ros::spin();
00356
00357 return 0;
00358 }
00359