00001
00020 #define USE_VISUALIZATION_DEBUG ///< Enable / Disable visualization
00021
00022
00023
00024 #include <mrpt/utils/CTicTac.h>
00025
00026 #ifdef USE_VISUALIZATION_DEBUG
00027 #include <mrpt/gui.h>
00028 #include <mrpt/base.h>
00029 #include <mrpt/opengl.h>
00030 #include <GL/gl.h>
00031 #include "CMyEllipsoid.h"
00032 #endif
00033
00034 #include <ros/ros.h>
00035 #include <rosbag/bag.h>
00036 #include <rosbag/view.h>
00037 #include <tf/transform_listener.h>
00038 #include <boost/foreach.hpp>
00039 #include <sensor_msgs/LaserScan.h>
00040 #include <message_filters/subscriber.h>
00041 #include <message_filters/sync_policies/approximate_time.h>
00042 #include <nav_msgs/Odometry.h>
00043 #include <nav_msgs/OccupancyGrid.h>
00044 #include <visualization_msgs/MarkerArray.h>
00045 #include <ndt_map.h>
00046 #include <tf/transform_broadcaster.h>
00047 #include "geometry_msgs/PoseWithCovarianceStamped.h"
00048 #include "geometry_msgs/Pose.h"
00049 #include "ndt_mcl.hpp"
00050
00051
00052
00056 #ifdef USE_VISUALIZATION_DEBUG
00057 #include "mcl_visualization.hpp"
00058 #endif
00059 ros::Publisher ndtmap_pub;
00060
00064 void sendMapToRviz(lslgeneric::NDTMap<pcl::PointXYZ> &map){
00065
00066 std::vector<lslgeneric::NDTCell<pcl::PointXYZ>*> ndts;
00067 ndts = map.getAllCells();
00068 fprintf(stderr,"SENDING MARKER ARRAY MESSAGE (%d components)\n",ndts.size());
00069 visualization_msgs::MarkerArray marray;
00070
00071 for(unsigned int i=0;i<ndts.size();i++){
00072 Eigen::Matrix3d cov = ndts[i]->getCov();
00073 Eigen::Vector3d m = ndts[i]->getMean();
00074
00075 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> Sol (cov);
00076
00077 Eigen::Matrix3d evecs;
00078 Eigen::Vector3d evals;
00079
00080 evecs = Sol.eigenvectors().real();
00081 evals = Sol.eigenvalues().real();
00082
00083 Eigen::Quaternion<double> q(evecs);
00084
00085 visualization_msgs::Marker marker;
00086 marker.header.frame_id = "world";
00087 marker.header.stamp = ros::Time();
00088 marker.ns = "NDT";
00089 marker.id = i;
00090 marker.type = visualization_msgs::Marker::SPHERE;
00091 marker.action = visualization_msgs::Marker::ADD;
00092 marker.pose.position.x = m[0];
00093 marker.pose.position.y = m[1];
00094 marker.pose.position.z = m[2];
00095
00096 marker.pose.orientation.x = q.x();
00097 marker.pose.orientation.y = q.y();
00098 marker.pose.orientation.z = q.z();
00099 marker.pose.orientation.w = q.w();
00100
00101 marker.scale.x = 100.0*evals(0);
00102 marker.scale.y = 100.0*evals(1);
00103 marker.scale.z = 100.0*evals(2);
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115 marker.color.a = 1.0;
00116 marker.color.r = 0.0;
00117 marker.color.g = 1.0;
00118 marker.color.b = 0.0;
00119
00120 marray.markers.push_back(marker);
00121 }
00122
00123 ndtmap_pub.publish(marray);
00124
00125 for(unsigned int i=0;i<ndts.size();i++){
00126 delete ndts[i];
00127 }
00128
00129 }
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152
00153
00154
00158 bool userInitialPose = false;
00159 bool hasNewInitialPose = false;
00160
00161 double ipos_x=0,ipos_y=0,ipos_yaw=0;
00162 double ivar_x=0,ivar_y=0,ivar_yaw=0;
00163
00164 ros::Subscriber initial_pose_sub_;
00165
00166 void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg){
00167 tf::Pose ipose;
00168 tf::poseMsgToTF(msg->pose.pose, ipose);
00169 ipos_x = ipose.getOrigin().x();
00170 ipos_y = ipose.getOrigin().y();
00171 double pitch, roll;
00172 ipose.getBasis().getEulerYPR(ipos_yaw,pitch,roll);
00173
00174 ivar_x = msg->pose.covariance[0];
00175 ivar_x = msg->pose.covariance[6];
00176 ivar_x = msg->pose.covariance[35];
00177
00178 hasNewInitialPose=true;
00179 }
00180
00181
00182
00183
00186
00189 Eigen::Affine3d getAsAffine(float x, float y, float yaw ){
00190 Eigen::Matrix3d m;
00191 m = Eigen::AngleAxisd(0, Eigen::Vector3d::UnitX())
00192 * Eigen::AngleAxisd(0, Eigen::Vector3d::UnitY())
00193 * Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ());
00194 Eigen::Translation3d v(x,y,0);
00195 Eigen::Affine3d T = v*m;
00196
00197 return T;
00198 }
00199
00209 NDTMCL<pcl::PointXYZ> *ndtmcl;
00211 float offx = 0;
00212 float offy = 0;
00213 float offa = 0;
00214 static bool has_sensor_offset_set = false;
00215 static bool isFirstLoad=true;
00216 Eigen::Affine3d Told,Todo;
00217
00218 ros::Publisher mcl_pub;
00219
00220
00221
00222
00223
00224 bool sendROSOdoMessage(Eigen::Vector3d mean,Eigen::Matrix3d cov, ros::Time ts){
00225 nav_msgs::Odometry O;
00226 static int seq = 0;
00227 O.header.stamp = ts;
00228 O.header.seq = seq;
00229 O.header.frame_id = "/world";
00230 O.child_frame_id = "/mcl_pose";
00231
00232 O.pose.pose.position.x = mean[0];
00233 O.pose.pose.position.y = mean[1];
00234 tf::Quaternion q;
00235 q.setRPY(0,0,mean[2]);
00236 O.pose.pose.orientation.x = q.getX();
00237 O.pose.pose.orientation.y = q.getY();
00238 O.pose.pose.orientation.z = q.getZ();
00239 O.pose.pose.orientation.w = q.getW();
00240
00241
00250 O.pose.covariance[0] = cov(0,0);
00251 O.pose.covariance[1] = cov(0,1);
00252 O.pose.covariance[2] = 0;
00253 O.pose.covariance[3] = 0;
00254 O.pose.covariance[4] = 0;
00255 O.pose.covariance[5] = 0;
00256
00257 O.pose.covariance[6] = cov(1,0);
00258 O.pose.covariance[7] = cov(1,1);
00259 O.pose.covariance[8] = 0;
00260 O.pose.covariance[9] = 0;
00261 O.pose.covariance[10] = 0;
00262 O.pose.covariance[11] = 0;
00263
00264 O.pose.covariance[12] = 0;
00265 O.pose.covariance[13] = 0;
00266 O.pose.covariance[14] = 0;
00267 O.pose.covariance[15] = 0;
00268 O.pose.covariance[16] = 0;
00269 O.pose.covariance[17] = 0;
00270
00271 O.pose.covariance[18] = 0;
00272 O.pose.covariance[19] = 0;
00273 O.pose.covariance[20] = 0;
00274 O.pose.covariance[21] = 0;
00275 O.pose.covariance[22] = 0;
00276 O.pose.covariance[23] = 0;
00277
00278 O.pose.covariance[24] = 0;
00279 O.pose.covariance[25] = 0;
00280 O.pose.covariance[26] = 0;
00281 O.pose.covariance[27] = 0;
00282 O.pose.covariance[28] = 0;
00283 O.pose.covariance[29] = 0;
00284
00285 O.pose.covariance[30] = 0;
00286 O.pose.covariance[31] = 0;
00287 O.pose.covariance[32] = 0;
00288 O.pose.covariance[33] = 0;
00289 O.pose.covariance[34] = 0;
00290 O.pose.covariance[35] = cov(2,2);
00291
00292 seq++;
00293 mcl_pub.publish(O);
00294
00295 static tf::TransformBroadcaster br;
00296 tf::Transform transform;
00297 transform.setOrigin( tf::Vector3(mean[0],mean[1], 0.0) );
00298
00299 transform.setRotation( q );
00300 br.sendTransform(tf::StampedTransform(transform, ts, "world", "mcl_pose"));
00301
00302 return true;
00303 }
00304
00305
00306
00311 mrpt::utils::CTicTac TT;
00312
00313 std::string tf_odo_topic = "odom_base_link";
00314 std::string tf_state_topic = "base_link";
00315 std::string tf_laser_link = "base_laser_link";
00316
00320 void callback(const sensor_msgs::LaserScan::ConstPtr& scan)
00321 {
00322 static int counter = 0;
00323 counter++;
00324
00325 static tf::TransformListener tf_listener;
00326 double looptime = TT.Tac();
00327 TT.Tic();
00328 fprintf(stderr,"Lt( %.1lfms %.1lfHz seq:%d) -",looptime*1000,1.0/looptime,scan->header.seq);
00329
00330 if(has_sensor_offset_set == false) return;
00331 double gx,gy,gyaw,x,y,yaw;
00332
00334 tf::StampedTransform transform;
00335 tf_listener.waitForTransform("world", tf_state_topic, scan->header.stamp,ros::Duration(1.0));
00337 try{
00338 tf_listener.lookupTransform("world", tf_state_topic, scan->header.stamp, transform);
00339 gyaw = tf::getYaw(transform.getRotation());
00340 gx = transform.getOrigin().x();
00341 gy = transform.getOrigin().y();
00342 }
00343 catch (tf::TransformException ex){
00344 ROS_ERROR("%s",ex.what());
00345 return;
00346 }
00347
00349 try{
00350 tf_listener.lookupTransform("world", tf_odo_topic, scan->header.stamp, transform);
00351 yaw = tf::getYaw(transform.getRotation());
00352 x = transform.getOrigin().x();
00353 y = transform.getOrigin().y();
00354 }
00355 catch (tf::TransformException ex){
00356 ROS_ERROR("%s",ex.what());
00357 return;
00358 }
00359
00360
00361 mrpt::utils::CTicTac tictac;
00362 tictac.Tic();
00363
00365 int N =(scan->angle_max - scan->angle_min)/scan->angle_increment;
00369
00370 Eigen::Affine3d T = getAsAffine(x,y,yaw);
00371 Eigen::Affine3d Tgt = getAsAffine(gx,gy,gyaw);
00372
00373 if(userInitialPose && hasNewInitialPose){
00374 gx = ipos_x;
00375 gy = ipos_y;
00376 gyaw = ipos_yaw;
00377 }
00378
00379 if(isFirstLoad || hasNewInitialPose){
00380 fprintf(stderr,"Initializing to (%lf, %lf, %lf)\n",gx,gy,gyaw);
00382 ndtmcl->initializeFilter(gx, gy,gyaw,0.2, 0.2, 2.0*M_PI/180.0, 150);
00383 Told = T;
00384 Todo = Tgt;
00385 hasNewInitialPose = false;
00386 }
00387
00389 Eigen::Affine3d Tmotion = Told.inverse() * T;
00390 Todo = Todo*Tmotion;
00391
00392 if(isFirstLoad==false){
00393 if( (Tmotion.translation().norm()<0.005 && fabs(Tmotion.rotation().eulerAngles(0,1,2)[2])<(0.2*M_PI/180.0))){
00394 Eigen::Vector3d dm = ndtmcl->getMean();
00395 Eigen::Matrix3d cov = ndtmcl->pf.getDistributionVariances();
00396 sendROSOdoMessage(dm,cov, scan->header.stamp);
00397 double Time = tictac.Tac();
00398 fprintf(stderr,"Time elapsed %.1lfms\n",Time*1000);
00399 return;
00400 }
00401 }
00402
00403 Told = T;
00404
00406 float dy =offy;
00407 float dx = offx;
00408 float alpha = atan2(dy,dx);
00409 float L = sqrt(dx*dx+dy*dy);
00410
00412 float lpx = L * cos(alpha);
00413 float lpy = L * sin(alpha);
00414 float lpa = offa;
00415
00417 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00418 for (int j=0;j<N;j++){
00419 double r = scan->ranges[j];
00420 if(r>=scan->range_min && r<scan->range_max && r>0.3 && r<20.0){
00421 double a = scan->angle_min + j*scan->angle_increment;
00422 pcl::PointXYZ pt;
00423 pt.x = r*cos(a+lpa)+lpx;
00424 pt.y = r*sin(a+lpa)+lpy;
00425 pt.z = 0.1+0.02 * (double)rand()/(double)RAND_MAX;
00426 cloud->push_back(pt);
00427 }
00428 }
00432 ndtmcl->updateAndPredict(Tmotion, *cloud);
00433
00434 Eigen::Vector3d dm = ndtmcl->getMean();
00435 Eigen::Matrix3d cov = ndtmcl->pf.getDistributionVariances();
00436
00437 double Time = tictac.Tac();
00438 fprintf(stderr,"Time elapsed %.1lfms (%lf %lf %lf) \n",Time*1000,dm[0],dm[1],dm[2]);
00439 isFirstLoad = false;
00441
00442 sendROSOdoMessage(dm,cov, scan->header.stamp);
00443
00444 if(counter%50==0){
00445 sendMapToRviz(ndtmcl->map);
00446 }
00447
00449 #ifdef USE_VISUALIZATION_DEBUG
00450 Eigen::Vector3d origin(dm[0] + L * cos(dm[2]+alpha),dm[1] + L * sin(dm[2]+alpha),0.1);
00451 Eigen::Affine3d ppos = getAsAffine(dm[0],dm[1],dm[2]);
00452
00453
00454 lslgeneric::transformPointCloudInPlace(ppos, *cloud);
00455 mrpt::opengl::COpenGLScenePtr &scene = win3D.get3DSceneAndLock();
00456 win3D.setCameraPointingToPoint(gx,gy,1);
00457 if(counter%2000==0) gl_points->clear();
00458 scene->clear();
00459 scene->insert(plane);
00460
00461 addMap2Scene(ndtmcl->map, origin, scene);
00462 addPoseCovariance(dm[0],dm[1],cov,scene);
00463 addScanToScene(scene, origin, cloud);
00464 addParticlesToWorld(ndtmcl->pf,Tgt.translation(),dm, Todo.translation());
00465 scene->insert(gl_points);
00466 scene->insert(gl_particles);
00467 win3D.unlockAccess3DScene();
00468 win3D.repaint();
00469
00470 if (win3D.keyHit())
00471 {
00472 mrpt::gui::mrptKeyModifier kmods;
00473 int key = win3D.getPushedKey(&kmods);
00474 }
00475 #endif
00476 }
00477
00478
00479 int main(int argc, char **argv){
00480 ros::init(argc, argv, "NDT-MCL");
00481 double resolution=0.4;
00482
00483 #ifdef USE_VISUALIZATION_DEBUG
00484 initializeScene();
00485 #endif
00486
00487 ros::NodeHandle n;
00488 ros::NodeHandle nh;
00489 ros::NodeHandle paramHandle ("~");
00490 TT.Tic();
00491
00492 std::string tf_base_link,input_laser_topic;
00493
00499 bool loadMap = false;
00500 std::string mapName("basement.ndmap");
00501
00502 bool saveMap = true;
00503 std::string output_map_name = std::string("ndt_mapper_output.ndmap");
00504
00510
00511 paramHandle.param<std::string>("input_laser_topic", input_laser_topic, std::string("/base_scan"));
00512 paramHandle.param<std::string>("tf_base_link", tf_state_topic, std::string("/base_link"));
00513 paramHandle.param<std::string>("tf_laser_link", tf_laser_link, std::string("/hokuyo1_link"));
00514
00515 bool use_sensor_pose;
00516 paramHandle.param<bool>("use_sensor_pose", use_sensor_pose, false);
00517 double sensor_pose_x, sensor_pose_y, sensor_pose_th;
00518 paramHandle.param<double>("sensor_pose_x", sensor_pose_x, 0.);
00519 paramHandle.param<double>("sensor_pose_y", sensor_pose_y, 0.);
00520 paramHandle.param<double>("sensor_pose_th", sensor_pose_th, 0.);
00521
00522 paramHandle.param<bool>("load_map_from_file", loadMap, false);
00523 paramHandle.param<std::string>("map_file_name", mapName, std::string("basement.ndmap"));
00524
00525 paramHandle.param<bool>("save_output_map", saveMap, true);
00526 paramHandle.param<std::string>("output_map_file_name", output_map_name, std::string("ndt_mapper_output.ndmap"));
00527
00528 paramHandle.param<double>("map_resolution", resolution , 0.2);
00529 bool forceSIR=false;
00530 paramHandle.param<bool>("forceSIR", forceSIR, false);
00531
00532 paramHandle.param<bool>("set_initial_pose", userInitialPose, false);
00533 paramHandle.param<double>("initial_pose_x", ipos_x, 0.);
00534 paramHandle.param<double>("initial_pose_y", ipos_y, 0.);
00535 paramHandle.param<double>("initial_pose_yaw", ipos_yaw, 0.);
00536
00537 if(userInitialPose==true) hasNewInitialPose=true;
00538
00544 fprintf(stderr,"USING RESOLUTION %lf\n",resolution);
00545 lslgeneric::NDTMap<pcl::PointXYZ> ndmap(new lslgeneric::LazyGrid<pcl::PointXYZ>(resolution));
00546
00547 ndmap.setMapSize(80.0, 80.0, 1.0);
00548
00549 if(loadMap){
00550 fprintf(stderr,"Loading Map from '%s'\n",mapName.c_str());
00551 ndmap.loadFromJFF(mapName.c_str());
00552 }
00553
00554 ndtmcl = new NDTMCL<pcl::PointXYZ>(resolution,ndmap,-0.5);
00555 if(forceSIR) ndtmcl->forceSIR=true;
00556
00557 fprintf(stderr,"*** FORCE SIR = %d****",forceSIR);
00563 mcl_pub = nh.advertise<nav_msgs::Odometry>("ndt_mcl",10);
00569 ros::Subscriber scansub=nh.subscribe(input_laser_topic, 1, callback);
00570
00571 ndtmap_pub = nh.advertise<visualization_msgs::MarkerArray>( "NDTMAP", 0 );
00572
00573 initial_pose_sub_ = nh.subscribe("initialpose", 1, initialPoseReceived);
00574
00575 offa = sensor_pose_th;
00576 offx = sensor_pose_x;
00577 offy = sensor_pose_y;
00578
00579
00580 has_sensor_offset_set = true;
00581
00582 fprintf(stderr,"Sensor Pose = (%lf %lf %lf)\n",offx, offy, offa);
00583
00584 ros::spin();
00585
00586
00587 return 0;
00588 }