33   threads_.push_back(std::make_unique<boost::thread>(
 
   49       bool queue_empty = 
true;
 
   51         boost::mutex::scoped_lock lock(
q_mutex_);
 
   52         queue_empty = 
q_.empty();
 
   55           scan_w_pose = 
q_.front();
 
   61               "Recommend stopping until message is gone if online mapping.",
 
   78   const sensor_msgs::LaserScan::ConstPtr& scan)
 
   94       " device for %s; discarding scan", scan->header.frame_id.c_str());
 
  101     boost::mutex::scoped_lock lock(
q_mutex_);
 
  102     q_.push(PosedScan(scan, pose));
 
  110   slam_toolbox_msgs::ClearQueue::Request& req,
 
  111   slam_toolbox_msgs::ClearQueue::Response& resp)
 
  114   ROS_INFO(
"SynchronousSlamToolbox: Clearing all queued scans to add to map.");
 
  125   slam_toolbox_msgs::DeserializePoseGraph::Request& req,
 
  126   slam_toolbox_msgs::DeserializePoseGraph::Response& resp)
 
  129   if (req.match_type == procType::LOCALIZE_AT_POSE)
 
  131     ROS_ERROR(
"Requested a localization deserialization " 
  132       "in non-localization mode.");
 
  140     slam_toolbox_msgs::Reset::Request& req,
 
  141     slam_toolbox_msgs::Reset::Response& resp)
 
  145     boost::mutex::scoped_lock lock(
q_mutex_);
 
  147     while (!
q_.empty()) {