@@ -46,16 +46,15 @@ SlamToolbox::SlamToolbox(ros::NodeHandle& nh)
4646    ROS_FATAL (" [RoboSAR:slam_toolbox_common:SlamToolbox] base_frames_.size() != odom_frames_.size()" 
4747  assert (base_frames_.size () == laser_topics_.size ());
4848  assert (base_frames_.size () == odom_frames_.size ());
49-   //  Create  map to compute odom  frame given base  frame
49+   //  Setup  map: base  frame to odom  frame
5050  for (size_t  idx = 0 ; idx < base_frames_.size (); idx++)
5151  {
5252    m_base_id_to_odom_id_[base_frames_[idx]] = odom_frames_[idx];
5353  }
54-   //  Set up pose helpers and laser assistants  for each robot
54+   //  Set up pose helpers for each robot
5555  for (size_t  idx = 0 ; idx < base_frames_.size (); idx++)
5656  {
5757    pose_helpers_.push_back (std::make_unique<pose_utils::GetPoseHelper>(tf_.get (), base_frames_[idx], odom_frames_[idx]));
58-     laser_assistants_[base_frames_[idx]] = std::make_unique<laser_utils::LaserAssistant>(nh_, tf_.get (), base_frames_[idx]); //  Assumes base frame = laser frame
5958  }
6059  scan_holder_ = std::make_unique<laser_utils::ScanHolder>(lasers_);
6160  map_saver_ = std::make_unique<map_saver::MapSaver>(nh_, map_name_);
@@ -90,7 +89,6 @@ SlamToolbox::~SlamToolbox()
9089  for (size_t  idx = 0 ; idx < pose_helpers_.size (); idx++)
9190  {
9291    pose_helpers_[idx].reset ();
93-     //  laser_assistants_.reset();
9492  }
9593  for (std::map<std::string,std::unique_ptr<laser_utils::LaserAssistant>>::iterator it = laser_assistants_.begin (); it != laser_assistants_.end (); it++)
9694  {
@@ -189,7 +187,7 @@ void SlamToolbox::setROSInterfaces(ros::NodeHandle& node)
189187    ROS_INFO (" Subscribing to scan: %s" c_str ());
190188    scan_filter_subs_.push_back (std::make_unique<message_filters::Subscriber<sensor_msgs::LaserScan> >(node, laser_topics_[idx], 5 ));
191189    scan_filters_.push_back (std::make_unique<tf2_ros::MessageFilter<sensor_msgs::LaserScan> >(*scan_filter_subs_.back (), *tf_, odom_frames_[idx], 5 , node));
192-     scan_filters_.back ()->registerCallback (boost::bind (&SlamToolbox::laserCallback, this , _1));
190+     scan_filters_.back ()->registerCallback (boost::bind (&SlamToolbox::laserCallback, this , _1, base_frames_[idx] ));
193191  }
194192}
195193
@@ -331,12 +329,19 @@ karto::LaserRangeFinder* SlamToolbox::getLaser(const
331329  sensor_msgs::LaserScan::ConstPtr& scan)
332330/* ****************************************************************************/ 
333331{
332+   //  Use laser scan ID to get base frame ID
334333  const  std::string& frame = scan->header .frame_id ;
335334  if (lasers_.find (frame) == lasers_.end ())
336335  {
337336    try 
338337    {
339-       lasers_[frame] = laser_assistants_[frame]->toLaserMetadata (*scan);
338+       std::map<std::string,std::unique_ptr<laser_utils::LaserAssistant>>::const_iterator it = laser_assistants_.find (frame);
339+       if (it == laser_assistants_.end ())
340+       {
341+         ROS_ERROR (" Failed to get requested laser assistant, aborting initialization (%s)" c_str ());
342+         return  nullptr ;
343+       }
344+       lasers_[frame] = it->second ->toLaserMetadata (*scan);
340345      dataset_->Add (lasers_[frame].getLaser (), true );
341346    }
342347    catch  (tf2::TransformException& e)
@@ -385,16 +390,27 @@ tf2::Stamped<tf2::Transform> SlamToolbox::setTransformFromPoses(
385390  const  bool & update_reprocessing_transform)
386391/* ****************************************************************************/ 
387392{
388-   //  Use base frame to look up odom frame
389-   std::string odom_frame = m_base_id_to_odom_id_[header.frame_id ];
393+   tf2::Stamped<tf2::Transform> odom_to_map;
394+   //  Use laser frame to look up base and odom frame
395+   std::string base_frame;
396+   {
397+     boost::mutex::scoped_lock l (laser_id_map_mutex_);
398+     std::map<std::string, std::string>::const_iterator it = m_laser_id_to_base_id_.find (header.frame_id );
399+     if (it == m_laser_id_to_base_id_.end ())
400+     {
401+       ROS_ERROR (" Requested laser frame ID not in map: %s" frame_id .c_str ());
402+       return  odom_to_map;
403+     }
404+     base_frame = it->second ;
405+   }
406+   const  std::string& odom_frame = m_base_id_to_odom_id_[base_frame];
390407  //  Compute the map->odom transform
391408  const  ros::Time& t = header.stamp ;
392-   tf2::Stamped<tf2::Transform> odom_to_map;
393409  tf2::Quaternion q (0 .,0 .,0 .,1.0 );
394410  q.setRPY (0 ., 0 ., corrected_pose.GetHeading ());
395411  tf2::Stamped<tf2::Transform> base_to_map (
396412    tf2::Transform (q, tf2::Vector3 (corrected_pose.GetX (),
397-     corrected_pose.GetY (), 0.0 )).inverse (), t, header. frame_id );  //  Assumes base frame = laser frame 
413+     corrected_pose.GetY (), 0.0 )).inverse (), t, base_frame); 
398414  try 
399415  {
400416    geometry_msgs::TransformStamped base_to_map_msg, odom_to_map_msg;
@@ -735,8 +751,14 @@ void SlamToolbox::loadSerializedPoseGraph(
735751        ROS_INFO (" Got scan!" 
736752        try 
737753        {
738-           lasers_[scan->header .frame_id ] =
739-             laser_assistants_[scan->header .frame_id ]->toLaserMetadata (*scan);
754+           const  std::string& frame = scan->header .frame_id ;
755+           std::map<std::string,std::unique_ptr<laser_utils::LaserAssistant>>::const_iterator it = laser_assistants_.find (frame);
756+           if (it == laser_assistants_.end ())
757+           {
758+             ROS_ERROR (" Failed to get requested laser assistant, aborting continue mapping (%s)" c_str ());
759+             exit (-1 );
760+           }
761+           lasers_[frame] = it->second ->toLaserMetadata (*scan);
740762          break ;
741763        }
742764        catch  (tf2::TransformException& e)
0 commit comments