2d_ndt_mcl_node.cpp
Go to the documentation of this file.
00001 
00020 #define USE_VISUALIZATION_DEBUG ///< Enable / Disable visualization
00021 
00022  
00023 #ifdef USE_VISUALIZATION_DEBUG
00024     #include <ndt_visualisation/ndt_viz.h>
00025 #endif
00026 
00027 #include <ros/ros.h>
00028 #include <rosbag/bag.h>
00029 #include <rosbag/view.h>
00030 #include <tf/transform_listener.h>
00031 #include <boost/foreach.hpp>
00032 #include <sensor_msgs/LaserScan.h>
00033 #include <message_filters/subscriber.h>
00034 #include <message_filters/sync_policies/approximate_time.h>
00035 #include <nav_msgs/Odometry.h>
00036 #include <nav_msgs/OccupancyGrid.h>
00037 #include <visualization_msgs/MarkerArray.h>
00038 #include <tf/transform_broadcaster.h>
00039 #include "geometry_msgs/PoseWithCovarianceStamped.h"
00040 #include "geometry_msgs/Pose.h"
00041 
00042 #include "ndt_mcl/ndt_mcl.h"
00043 #include <ndt_map/ndt_map.h>
00044 
00045 
00046 
00050 #ifdef USE_VISUALIZATION_DEBUG
00051 NDTViz ndt_viz;
00052 #endif
00053 ros::Publisher ndtmap_pub; 
00054 
00058 void sendMapToRviz(lslgeneric::NDTMap &map){
00059 
00060         std::vector<lslgeneric::NDTCell*> ndts;
00061         ndts = map.getAllCells();
00062         fprintf(stderr,"SENDING MARKER ARRAY MESSAGE (%u components)\n",ndts.size());
00063         visualization_msgs::MarkerArray marray;
00064         
00065         for(unsigned int i=0;i<ndts.size();i++){
00066                 Eigen::Matrix3d cov = ndts[i]->getCov();
00067                 Eigen::Vector3d m = ndts[i]->getMean();
00068                 
00069                 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> Sol (cov);
00070 
00071     Eigen::Matrix3d evecs;
00072     Eigen::Vector3d evals;
00073 
00074     evecs = Sol.eigenvectors().real();
00075     evals = Sol.eigenvalues().real();
00076     
00077     Eigen::Quaternion<double> q(evecs);
00078         
00079                 visualization_msgs::Marker marker;
00080                 marker.header.frame_id = "world";
00081                 marker.header.stamp = ros::Time();
00082                 marker.ns = "NDT";
00083                 marker.id = i;
00084                 marker.type = visualization_msgs::Marker::SPHERE;
00085                 marker.action = visualization_msgs::Marker::ADD;
00086                 marker.pose.position.x = m[0];
00087                 marker.pose.position.y = m[1];
00088                 marker.pose.position.z = m[2];
00089                 
00090                 marker.pose.orientation.x = q.x();
00091                 marker.pose.orientation.y = q.y();
00092                 marker.pose.orientation.z = q.z();
00093                 marker.pose.orientation.w = q.w();
00094                 
00095                 marker.scale.x = 100.0*evals(0);
00096                 marker.scale.y = 100.0*evals(1);
00097                 marker.scale.z = 100.0*evals(2);
00098                 /*
00099                 marker.pose.orientation.x = 0;
00100                 marker.pose.orientation.y = 0;
00101                 marker.pose.orientation.z = 0;
00102                 marker.pose.orientation.w = 1;
00103 
00104                 marker.scale.x = 1;
00105                 marker.scale.y = 1;
00106                 marker.scale.z = 1;
00107         */      
00108                 
00109                 marker.color.a = 1.0;
00110                 marker.color.r = 0.0;
00111                 marker.color.g = 1.0;
00112                 marker.color.b = 0.0;
00113                 
00114                 marray.markers.push_back(marker);
00115         }
00116         
00117         ndtmap_pub.publish(marray);
00118         
00119         for(unsigned int i=0;i<ndts.size();i++){
00120                 delete ndts[i];
00121         }
00122 
00123 }
00124 
00125 
00126 
00127 /*
00128  * enter code here
00129 (eigValues,eigVectors) = numpy.linalg.eig (covMat)
00130 
00131 eigx_n=-PyKDL.Vector(eigVectors[0,0],eigVectors[1,0],eigVectors[2,0])
00132 eigy_n=-PyKDL.Vector(eigVectors[0,1],eigVectors[1,1],eigVectors[2,1])
00133 eigz_n=-PyKDL.Vector(eigVectors[0,2],eigVectors[1,2],eigVectors[2,2])
00134 
00135 rot = PyKDL.Rotation (eigx_n,eigy_n,eigz_n)
00136 quat = rot.GetQuaternion ()
00137 
00138 #painting the Gaussian Ellipsoid Marker
00139 marker.pose.orientation.x =quat[0]
00140 marker.pose.orientation.y = quat[1]
00141 marker.pose.orientation.z = quat[2]
00142 marker.pose.orientation.w = quat[3]
00143 marker.scale.x = eigValues[0]
00144 marker.scale.y = eigValues[1]
00145 marker.scale.z =eigValues[2]
00146 */ 
00147 
00148 
00152 bool userInitialPose = false;
00153 bool hasNewInitialPose = false;
00154 
00155 double ipos_x=0,ipos_y=0,ipos_yaw=0;
00156 double ivar_x=0,ivar_y=0,ivar_yaw=0;
00157 
00158 ros::Subscriber initial_pose_sub_;
00159 
00160 void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg){
00161         tf::Pose ipose;
00162   tf::poseMsgToTF(msg->pose.pose, ipose);
00163   ipos_x = ipose.getOrigin().x();
00164   ipos_y = ipose.getOrigin().y();
00165   double pitch, roll;
00166   ipose.getBasis().getEulerYPR(ipos_yaw,pitch,roll);
00167   
00168   ivar_x = msg->pose.covariance[0];
00169   ivar_x = msg->pose.covariance[6];
00170   ivar_x = msg->pose.covariance[35];
00171   
00172   hasNewInitialPose=true;
00173 }
00174 
00175 
00176 
00177 
00180 
00183 Eigen::Affine3d getAsAffine(float x, float y, float yaw ){
00184         Eigen::Matrix3d m;
00185         m = Eigen::AngleAxisd(0, Eigen::Vector3d::UnitX())
00186                         * Eigen::AngleAxisd(0, Eigen::Vector3d::UnitY())
00187                         * Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ());
00188         Eigen::Translation3d v(x,y,0);
00189         Eigen::Affine3d T = v*m;
00190         
00191         return T;
00192 }
00193 
00203 NDTMCL *ndtmcl;
00205 float offx = 0;
00206 float offy = 0;
00207 float offa = 0;
00208 static bool has_sensor_offset_set = false;
00209 static bool isFirstLoad=true;
00210 Eigen::Affine3d Told,Todo;
00211 
00212 ros::Publisher mcl_pub; 
00213 
00214 
00215 
00216 
00217 
00218 bool sendROSOdoMessage(Eigen::Vector3d mean,Eigen::Matrix3d cov, ros::Time ts){
00219         nav_msgs::Odometry O;
00220         static int seq = 0;
00221         O.header.stamp = ts;
00222         O.header.seq = seq;
00223         O.header.frame_id = "/world";
00224         O.child_frame_id = "/mcl_pose";
00225         
00226         O.pose.pose.position.x = mean[0];
00227         O.pose.pose.position.y = mean[1];
00228         tf::Quaternion q;
00229         q.setRPY(0,0,mean[2]);
00230         O.pose.pose.orientation.x = q.getX();
00231         O.pose.pose.orientation.y = q.getY();
00232         O.pose.pose.orientation.z = q.getZ();
00233         O.pose.pose.orientation.w = q.getW();
00234         
00235 
00244         O.pose.covariance[0] = cov(0,0);
00245         O.pose.covariance[1] = cov(0,1);
00246         O.pose.covariance[2] = 0;
00247         O.pose.covariance[3] = 0;
00248         O.pose.covariance[4] = 0;
00249         O.pose.covariance[5] = 0;
00250         
00251         O.pose.covariance[6] = cov(1,0);
00252         O.pose.covariance[7] = cov(1,1);
00253         O.pose.covariance[8] = 0;
00254         O.pose.covariance[9] = 0;
00255         O.pose.covariance[10] = 0;
00256         O.pose.covariance[11] = 0;
00257         
00258         O.pose.covariance[12] = 0;
00259         O.pose.covariance[13] = 0;
00260         O.pose.covariance[14] = 0;
00261         O.pose.covariance[15] = 0;
00262         O.pose.covariance[16] = 0;
00263         O.pose.covariance[17] = 0;
00264         
00265         O.pose.covariance[18] = 0;
00266         O.pose.covariance[19] = 0;
00267         O.pose.covariance[20] = 0;
00268         O.pose.covariance[21] = 0;
00269         O.pose.covariance[22] = 0;
00270         O.pose.covariance[23] = 0;
00271         
00272         O.pose.covariance[24] = 0;
00273         O.pose.covariance[25] = 0;
00274         O.pose.covariance[26] = 0;
00275         O.pose.covariance[27] = 0;
00276         O.pose.covariance[28] = 0;
00277         O.pose.covariance[29] = 0;
00278         
00279         O.pose.covariance[30] = 0;
00280         O.pose.covariance[31] = 0;
00281         O.pose.covariance[32] = 0;
00282         O.pose.covariance[33] = 0;
00283         O.pose.covariance[34] = 0;
00284         O.pose.covariance[35] = cov(2,2);
00285         
00286         seq++;
00287         mcl_pub.publish(O);
00288         
00289         static tf::TransformBroadcaster br;
00290   tf::Transform transform;
00291   transform.setOrigin( tf::Vector3(mean[0],mean[1], 0.0) );
00292   
00293         transform.setRotation( q );
00294   br.sendTransform(tf::StampedTransform(transform, ts, "world", "mcl_pose"));
00295         
00296         return true;
00297 }
00298 
00299 
00300 
00305 double time_end;
00306 std::string tf_odo_topic =   "odom_base_link";
00307 std::string tf_state_topic = "base_link";
00308 std::string tf_laser_link =  "base_laser_link";
00309 
00310 double getDoubleTime()
00311 {
00312     struct timeval time;
00313     gettimeofday(&time,NULL);
00314     return time.tv_sec + time.tv_usec * 1e-6;
00315 }
00319 void callback(const sensor_msgs::LaserScan::ConstPtr& scan)
00320 {
00321         static int counter = 0;
00322         counter++;
00323         
00324         static tf::TransformListener tf_listener;
00325         double time_now = getDoubleTime();  
00326         double looptime = time_end - time_now;
00327         fprintf(stderr,"Lt( %.1lfms %.1lfHz seq:%d) -",looptime*1000,1.0/looptime,scan->header.seq);
00328         
00329         if(has_sensor_offset_set == false) return;
00330         double gx,gy,gyaw,x,y,yaw;
00331         
00333         tf::StampedTransform transform;
00334         tf_listener.waitForTransform("world", tf_state_topic, scan->header.stamp,ros::Duration(1.0));
00336         try{
00337                 tf_listener.lookupTransform("world", tf_state_topic, scan->header.stamp, transform);
00338                 gyaw = tf::getYaw(transform.getRotation());  
00339           gx = transform.getOrigin().x();
00340           gy = transform.getOrigin().y();
00341         }
00342         catch (tf::TransformException ex){
00343                 ROS_ERROR("%s",ex.what());
00344                 return;
00345         }
00346         
00348         try{
00349                 tf_listener.lookupTransform("world", tf_odo_topic, scan->header.stamp, transform);
00350                 yaw = tf::getYaw(transform.getRotation());  
00351           x = transform.getOrigin().x();
00352           y = transform.getOrigin().y();
00353         }
00354         catch (tf::TransformException ex){
00355                 ROS_ERROR("%s",ex.what());
00356                 return;
00357         }
00358         
00359                 
00361         int N =(scan->angle_max - scan->angle_min)/scan->angle_increment;
00365         
00366         Eigen::Affine3d T = getAsAffine(x,y,yaw);
00367         Eigen::Affine3d Tgt = getAsAffine(gx,gy,gyaw);
00368         
00369         if(userInitialPose && hasNewInitialPose){
00370                 gx = ipos_x;
00371                 gy = ipos_y;
00372                 gyaw = ipos_yaw;
00373         }
00374         
00375         if(isFirstLoad || hasNewInitialPose){
00376                 fprintf(stderr,"Initializing to (%lf, %lf, %lf)\n",gx,gy,gyaw);
00378                 ndtmcl->initializeFilter(gx, gy,gyaw,0.2, 0.2, 2.0*M_PI/180.0, 150);
00379                 Told = T;
00380                 Todo = Tgt;
00381                 hasNewInitialPose = false;
00382         }
00383         
00385         Eigen::Affine3d Tmotion = Told.inverse() * T;
00386         Todo = Todo*Tmotion; 
00387         
00388         if(isFirstLoad==false){
00389                 if( (Tmotion.translation().norm()<0.005 && fabs(Tmotion.rotation().eulerAngles(0,1,2)[2])<(0.2*M_PI/180.0))){
00390                         Eigen::Vector3d dm = ndtmcl->getMean();
00391                         Eigen::Matrix3d cov = ndtmcl->pf.getDistributionVariances();
00392                         sendROSOdoMessage(dm,cov, scan->header.stamp);
00393                         return;
00394                 }
00395         }
00396         
00397         Told = T;
00398         
00400         float dy =offy;
00401         float dx = offx;
00402         float alpha = atan2(dy,dx);
00403         float L = sqrt(dx*dx+dy*dy);
00404         
00406         float lpx = L * cos(alpha);
00407         float lpy = L * sin(alpha);
00408         float lpa = offa;
00409         
00411         pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>); 
00412         for (int j=0;j<N;j++){
00413                 double r  = scan->ranges[j];
00414                 if(r>=scan->range_min && r<scan->range_max && r>0.3 && r<20.0){
00415                         double a  = scan->angle_min + j*scan->angle_increment;
00416                         pcl::PointXYZ pt;
00417                         pt.x = r*cos(a+lpa)+lpx;
00418                         pt.y = r*sin(a+lpa)+lpy;
00419                         pt.z = 0.1+0.02 * (double)rand()/(double)RAND_MAX;
00420                         cloud->push_back(pt);
00421                 }
00422         }
00426         ndtmcl->updateAndPredict(Tmotion, *cloud); 
00427         
00428         Eigen::Vector3d dm = ndtmcl->getMean(); 
00429         Eigen::Matrix3d cov = ndtmcl->pf.getDistributionVariances(); 
00430 
00431         time_end = getDoubleTime();
00432         fprintf(stderr,"Time elapsed %.1lfms (%lf %lf %lf) \n",time_end-time_now,dm[0],dm[1],dm[2]);
00433         isFirstLoad = false;
00435         
00436         sendROSOdoMessage(dm,cov, scan->header.stamp); 
00437         
00438         if(counter%50==0){
00439                 sendMapToRviz(ndtmcl->map);
00440         }
00441         
00443 #ifdef USE_VISUALIZATION_DEBUG
00444         if(counter%500==0){
00445             ndt_viz.clear();
00446             ndt_viz.plotNDTSAccordingToOccupancy(-1,&ndtmcl->map);
00447 
00448         }
00449         ndt_viz.clearParticles();
00450         for(int i=0;i<ndtmcl->pf.NumOfParticles;i++){
00451             ndt_viz.addParticle(ndtmcl->pf.Particles[i].x, ndtmcl->pf.Particles[i].y, 0.5, 1.0, 1.0, 1.0);
00452         }
00453 
00454         ndt_viz.addTrajectoryPoint(dm[0],dm[1],0.5,1.0,0,0);    
00455         ndt_viz.addTrajectoryPoint(Tgt.translation()(0), Tgt.translation()(1),0.5,1.0,1.0,1.0); 
00456         ndt_viz.addTrajectoryPoint(Todo.translation()(0), Todo.translation()(1),0.5,0.0,1.0,0.0);       
00457 
00458         ndt_viz.displayParticles();
00459         ndt_viz.displayTrajectory();
00460         ndt_viz.win3D->setCameraPointingToPoint(dm[0],dm[1],3.0);
00461         ndt_viz.repaint();
00462         
00463 #endif
00464 }
00465 
00466 
00467 int main(int argc, char **argv){
00468         ros::init(argc, argv, "NDT-MCL");
00469         double resolution=0.4;
00470         
00471         ros::NodeHandle n;
00472         ros::NodeHandle nh;
00473         ros::NodeHandle paramHandle ("~");
00474         time_end = getDoubleTime();
00475         
00476         std::string tf_base_link,input_laser_topic; 
00477         
00483         bool loadMap = false; 
00484         std::string mapName("basement.ndmap"); 
00485         
00486         bool saveMap = true;                                            
00487         std::string output_map_name = std::string("ndt_mapper_output.ndmap");
00488         
00494         
00495         paramHandle.param<std::string>("input_laser_topic", input_laser_topic, std::string("/base_scan"));
00496         paramHandle.param<std::string>("tf_base_link", tf_state_topic, std::string("/base_link"));
00497         paramHandle.param<std::string>("tf_laser_link", tf_laser_link, std::string("/hokuyo1_link"));
00498         
00499         bool use_sensor_pose;
00500         paramHandle.param<bool>("use_sensor_pose", use_sensor_pose, false);
00501         double sensor_pose_x, sensor_pose_y, sensor_pose_th;
00502         paramHandle.param<double>("sensor_pose_x", sensor_pose_x, 0.);
00503         paramHandle.param<double>("sensor_pose_y", sensor_pose_y, 0.);
00504         paramHandle.param<double>("sensor_pose_th", sensor_pose_th, 0.);
00505         
00506         paramHandle.param<bool>("load_map_from_file", loadMap, false);
00507         paramHandle.param<std::string>("map_file_name", mapName, std::string("basement.ndmap"));
00508         
00509         paramHandle.param<bool>("save_output_map", saveMap, true);
00510         paramHandle.param<std::string>("output_map_file_name", output_map_name, std::string("ndt_mapper_output.ndmap"));
00511         
00512         paramHandle.param<double>("map_resolution", resolution , 0.2);
00513         bool forceSIR=false;
00514         paramHandle.param<bool>("forceSIR", forceSIR, false);
00515                 
00516         paramHandle.param<bool>("set_initial_pose", userInitialPose, false);
00517         paramHandle.param<double>("initial_pose_x", ipos_x, 0.);
00518         paramHandle.param<double>("initial_pose_y", ipos_y, 0.);
00519         paramHandle.param<double>("initial_pose_yaw", ipos_yaw, 0.);
00520         
00521         if(userInitialPose==true) hasNewInitialPose=true;
00522         
00528         fprintf(stderr,"USING RESOLUTION %lf\n",resolution);
00529         lslgeneric::NDTMap ndmap(new lslgeneric::LazyGrid(resolution));
00530 
00531         ndmap.setMapSize(80.0, 80.0, 1.0);
00532         
00533         if(loadMap){
00534                 fprintf(stderr,"Loading Map from '%s'\n",mapName.c_str());
00535                 ndmap.loadFromJFF(mapName.c_str());
00536         }
00537         
00538         ndtmcl = new NDTMCL(resolution,ndmap,-0.5);
00539         if(forceSIR) ndtmcl->forceSIR=true;
00540 
00541         fprintf(stderr,"*** FORCE SIR = %d****",forceSIR);
00547         mcl_pub = nh.advertise<nav_msgs::Odometry>("ndt_mcl",10);
00553         ros::Subscriber scansub=nh.subscribe(input_laser_topic, 1, callback);
00554         
00555         ndtmap_pub = nh.advertise<visualization_msgs::MarkerArray>( "NDTMAP", 0 );
00556         
00557         initial_pose_sub_ = nh.subscribe("initialpose", 1, initialPoseReceived);
00558 
00559         offa = sensor_pose_th;
00560         offx = sensor_pose_x;
00561         offy = sensor_pose_y;
00562         
00563         
00564         has_sensor_offset_set = true;
00565         
00566         fprintf(stderr,"Sensor Pose = (%lf %lf %lf)\n",offx, offy, offa);       
00567         
00568         ros::spin();
00569 
00570         
00571         return 0;
00572 }


ndt_mcl
Author(s): Jari Saarinen
autogenerated on Wed Aug 26 2015 15:25:02