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 "polar_scan_matcher/psm_node.h"
00030 
00031 int main (int argc, char** argv)
00032 {
00033   ros::init(argc, argv, "PolarScanMatching Node");
00034   PSMNode psmNode;
00035   ros::spin();
00036 }
00037 
00038 PSMNode::PSMNode()
00039 {
00040   ROS_INFO("Creating PolarScanMatching node");
00041 
00042   ros::NodeHandle nh;
00043 
00044   initialized_   = false;
00045   totalDuration_ = 0.0;
00046   scansCount_    = 0;
00047 
00048   prevWorldToBase_.setIdentity();
00049 
00050   getParams();  
00051 
00052   scanSubscriber_ = nh.subscribe (scanTopic_, 10, &PSMNode::scanCallback, this);
00053   imuSubscriber_  = nh.subscribe (imuTopic_,  10, &PSMNode::imuCallback,  this);
00054   posePublisher_  = nh.advertise<geometry_msgs::Pose2D>(poseTopic_, 10);
00055 }
00056 
00057 PSMNode::~PSMNode()
00058 {
00059   ROS_INFO("Destroying PolarScanMatching node");
00060 }
00061 
00062 void PSMNode::getParams()
00063 {
00064   ros::NodeHandle nh_private("~");
00065 
00066   std::string odometryType;
00067 
00068   
00069   
00070   if (!nh_private.getParam ("world_frame", worldFrame_))
00071     worldFrame_ = "world";
00072   if (!nh_private.getParam ("base_frame", baseFrame_))
00073     baseFrame_ = "base_link";
00074   if (!nh_private.getParam ("publish_tf", publishTf_))
00075     publishTf_ = true;
00076   if (!nh_private.getParam ("publish_pose", publishPose_))
00077     publishPose_ = true;
00078   if (!nh_private.getParam ("odometry_type", odometryType))
00079     odometryType = "none";
00080 
00081   if (odometryType.compare("none") == 0)
00082   {
00083     useTfOdometry_  = false;
00084     useImuOdometry_ = false;
00085   }
00086   else if (odometryType.compare("tf") == 0)
00087   {
00088     useTfOdometry_  = true;
00089     useImuOdometry_ = false;
00090   }
00091   else if (odometryType.compare("imu") == 0)
00092   {
00093     useTfOdometry_  = false;
00094     useImuOdometry_ = true;
00095   }
00096   else
00097   {
00098     ROS_WARN("Unknown value of odometry_type parameter passed to psm_node. \
00099               Using default value (\"none\")");
00100     useTfOdometry_  = false;
00101     useImuOdometry_ = false;
00102   }
00103 
00104   
00105 
00106   if (!nh_private.getParam ("min_valid_points", minValidPoints_))
00107     minValidPoints_ = 200;
00108   if (!nh_private.getParam ("search_window", searchWindow_))
00109     searchWindow_ = 40;
00110   if (!nh_private.getParam ("max_error", maxError_))
00111     maxError_ = 0.20;
00112   if (!nh_private.getParam ("max_iterations", maxIterations_))
00113     maxIterations_ = 20;
00114   if (!nh_private.getParam ("stop_condition", stopCondition_))
00115     stopCondition_ = 0.01;
00116 }
00117 
00118 bool PSMNode::initialize(const sensor_msgs::LaserScan& scan)
00119 {
00120   laserFrame_ = scan.header.frame_id;
00121 
00122   
00123 
00124   tf::StampedTransform baseToLaserTf;
00125   try
00126   {
00127    tfListener_.waitForTransform(baseFrame_, scan.header.frame_id, scan.header.stamp, ros::Duration(1.0));
00128    tfListener_.lookupTransform (baseFrame_, scan.header.frame_id, scan.header.stamp, baseToLaserTf);
00129   }
00130   catch (tf::TransformException ex)
00131   {
00132     ROS_WARN("ScanMatcherNode: Could get initial laser transform, skipping scan (%s)", ex.what());
00133     return false;
00134   }
00135   baseToLaser_ = baseToLaserTf;
00136   laserToBase_ = baseToLaser_.inverse();
00137 
00138   
00139 
00140   matcher_.PM_L_POINTS         = scan.ranges.size();
00141 
00142   matcher_.PM_FOV              = (scan.angle_max - scan.angle_min) * 180.0 / M_PI;
00143   matcher_.PM_MAX_RANGE        = scan.range_max * ROS_TO_PM;
00144 
00145   matcher_.PM_TIME_DELAY       = 0.00;
00146 
00147   matcher_.PM_MIN_VALID_POINTS = minValidPoints_;
00148   matcher_.PM_SEARCH_WINDOW    = searchWindow_;
00149   matcher_.PM_MAX_ERROR        = maxError_ * ROS_TO_PM;
00150 
00151   matcher_.PM_MAX_ITER         = maxIterations_;
00152   matcher_.PM_MAX_ITER_ICP     = maxIterations_;
00153   matcher_.PM_STOP_COND        = stopCondition_ * ROS_TO_PM;
00154   matcher_.PM_STOP_COND_ICP    = stopCondition_ * ROS_TO_PM;
00155 
00156   matcher_.pm_init();
00157 
00158   
00159 
00160   getCurrentEstimatedPose(prevWorldToBase_, scan);
00161 
00162   
00163 
00164   btTransform t;
00165   t.setIdentity();
00166   prevPMScan_ = new PMScan(scan.ranges.size());
00167   rosToPMScan(scan, t, prevPMScan_);
00168 
00169   return true;
00170 }
00171 
00172 void PSMNode::imuCallback (const sensor_msgs::Imu& imuMsg)
00173 {
00174   imuMutex_.lock();
00175   btQuaternion q(imuMsg.orientation.x, imuMsg.orientation.y, imuMsg.orientation.z, imuMsg.orientation.w);
00176   btMatrix3x3 m(q);
00177   double temp;
00178   m.getRPY(temp, temp, currImuAngle_);
00179   imuMutex_.unlock();
00180 }
00181 
00182 void PSMNode::scanCallback(const sensor_msgs::LaserScan& scan)
00183 {
00184   ROS_DEBUG("Received scan");
00185   scansCount_++;
00186 
00187   struct timeval start, end;
00188   gettimeofday(&start, NULL);
00189 
00190   
00191 
00192   if (!initialized_)
00193   {   
00194     initialized_ = initialize(scan);
00195     if (initialized_) ROS_INFO("Matcher initialized");
00196     return;
00197   }
00198   
00199   
00200 
00201   
00202   
00203   
00204   
00205   
00206 
00207   prevPMScan_->rx = 0;
00208   prevPMScan_->ry = 0;
00209   prevPMScan_->th = 0; 
00210 
00211   btTransform currWorldToBase;
00212   btTransform change;
00213   change.setIdentity();
00214 
00215   
00216   if (useTfOdometry_) 
00217   {
00218     
00219     
00220 
00221     getCurrentEstimatedPose(currWorldToBase, scan);
00222     change = laserToBase_ * prevWorldToBase_.inverse() * currWorldToBase * baseToLaser_;
00223   }
00224   else if (useImuOdometry_)
00225   {
00226     imuMutex_.lock();
00227     double dTheta = currImuAngle_ - prevImuAngle_;
00228     prevImuAngle_ = currImuAngle_;
00229     change.getRotation().setRPY(0.0, 0.0, dTheta);
00230     imuMutex_.unlock();
00231   }
00232 
00233   PMScan * currPMScan = new PMScan(scan.ranges.size());
00234   rosToPMScan(scan, change, currPMScan);
00235   
00236   try
00237   {         
00238     matcher_.pm_psm(prevPMScan_, currPMScan);                         
00239   }
00240   catch(int err)
00241   {
00242     ROS_WARN("Error in scan matching");
00243     delete prevPMScan_;
00244     prevPMScan_ = currPMScan;
00245     return;
00246   };    
00247 
00248   
00249 
00250   
00251   
00252   double dx =  currPMScan->ry / ROS_TO_PM;
00253   double dy = -currPMScan->rx / ROS_TO_PM;
00254   double da =  currPMScan->th; 
00255 
00256   
00257   
00258   change.setOrigin(btVector3(dx, dy, 0.0));
00259   btQuaternion q;
00260   q.setRPY(0, 0, da);
00261   change.setRotation(q);
00262   
00263   
00264    
00265   currWorldToBase = prevWorldToBase_ * baseToLaser_ * change * laserToBase_;
00266 
00267   if (publishTf_  ) publishTf  (currWorldToBase, scan.header.stamp);
00268   if (publishPose_) publishPose(currWorldToBase);
00269 
00270   
00271 
00272   delete prevPMScan_;
00273   prevPMScan_      = currPMScan;
00274   prevWorldToBase_ = currWorldToBase;
00275 
00276   
00277 
00278   gettimeofday(&end, NULL);
00279   double dur = ((end.tv_sec   * 1000000 + end.tv_usec  ) - 
00280                 (start.tv_sec * 1000000 + start.tv_usec)) / 1000.0;
00281   totalDuration_ += dur;
00282   double ave = totalDuration_/scansCount_;
00283 
00284   ROS_INFO("dur:\t %.3f ms \t ave:\t %.3f ms", dur, ave);
00285 }
00286 
00287 void PSMNode::publishTf(const btTransform& transform, 
00288                                   const ros::Time& time)
00289 {
00290   tf::StampedTransform transformMsg (transform, time, worldFrame_, baseFrame_);
00291   tfBroadcaster_.sendTransform (transformMsg);
00292 }
00293 
00294 void PSMNode::publishPose(const btTransform& transform)
00295 {
00296   geometry_msgs::Pose2D pose;
00297   tfToPose2D(transform, pose);
00298 
00299   posePublisher_.publish(pose);
00300 }
00301 
00302 void PSMNode::rosToPMScan(const sensor_msgs::LaserScan& scan, 
00303                           const btTransform& change,
00304                                 PMScan* pmScan)
00305 {
00306   geometry_msgs::Pose2D pose;
00307   tfToPose2D(change, pose);
00308 
00309   
00310 
00311   pmScan->rx = pose.x * ROS_TO_PM;
00312   pmScan->ry = pose.y * ROS_TO_PM;
00313   pmScan->th = pose.theta;
00314 
00315   for (int i = 0; i < scan.ranges.size(); ++i)
00316   {
00317     if (scan.ranges[i] == 0) 
00318     {
00319       pmScan->r[i] = 99999;  
00320     }
00321     else
00322     {
00323       pmScan->r[i] = scan.ranges[i] * ROS_TO_PM;
00324       pmScan->x[i] = (pmScan->r[i]) * matcher_.pm_co[i];
00325       pmScan->y[i] = (pmScan->r[i]) * matcher_.pm_si[i];
00326       pmScan->bad[i] = 0;
00327     }
00328 
00329     pmScan->bad[i] = 0;
00330   }
00331 
00332   matcher_.pm_median_filter  (pmScan);
00333   matcher_.pm_find_far_points(pmScan);
00334   matcher_.pm_segment_scan   (pmScan);  
00335 }
00336 
00337 void PSMNode::getCurrentEstimatedPose(btTransform& worldToBase, 
00338                                       const sensor_msgs::LaserScan& scanMsg)
00339 {
00340   tf::StampedTransform worldToBaseTf;
00341   try
00342   {
00343      tfListener_.lookupTransform (worldFrame_, baseFrame_, scanMsg.header.stamp, worldToBaseTf);
00344   }
00345   catch (tf::TransformException ex)
00346   {
00347     
00348     ROS_WARN("Transform unavailable, using last estimated pose (%s)", ex.what());
00349     worldToBase = prevWorldToBase_;
00350     return;
00351   }
00352   worldToBase = worldToBaseTf;
00353 }
00354 
00355 void PSMNode::pose2DToTf(const geometry_msgs::Pose2D& pose, btTransform& t)
00356 {
00357   t.setOrigin(btVector3(pose.x, pose.y, 0.0));
00358   btQuaternion q;
00359   q.setRPY(0, 0, pose.theta);
00360   t.setRotation(q);
00361 }
00362 
00363 void PSMNode::tfToPose2D(const btTransform& t, geometry_msgs::Pose2D& pose)
00364 {
00365   btMatrix3x3 m(t.getRotation());
00366   double roll, pitch, yaw;
00367   m.getRPY(roll, pitch, yaw);
00368 
00369   pose.x = t.getOrigin().getX();
00370   pose.y = t.getOrigin().getY();
00371   pose.theta = yaw;
00372 }