36   nh_private_(nh_private)
 
   38   ROS_INFO (
"Starting LaserScanSplitter");
 
   42   std::string topics_string;
 
   43   std::string frames_string;
 
   44   std::string sizes_string;
 
   47     topics_string = 
"scan1 scan2";
 
   49     frames_string = 
"laser laser";
 
   51     sizes_string = 
"256 256";
 
   57   std::vector<std::string> sizes_tokens;
 
   58   tokenize (sizes_string, sizes_tokens);
 
   61   for (
unsigned int i = 0; i < sizes_tokens.size (); i++)
 
   63     sizes_.push_back (atoi (sizes_tokens[i].c_str ()));
 
   73                   "LaserScanSplitter: Invalid parameters. Quitting.");
 
   87 LaserScanSplitter::~LaserScanSplitter ()
 
   89   ROS_INFO (
"Destroying LaserScanSplitter");
 
   95   if (
size_sum_ != scan_msg->ranges.size ())
 
   97     ROS_WARN (
"LaserScanSplitter: Received a laser scan with size (%d) \ 
   98       incompatible to input parameters. Skipping scan.", (
int)scan_msg->ranges.size());
 
  107     sensor_msgs::LaserScan::Ptr scan_segment;
 
  108     scan_segment = boost::make_shared<sensor_msgs::LaserScan>();
 
  110     scan_segment->header = scan_msg->header;
 
  111     scan_segment->range_min = scan_msg->range_min;
 
  112     scan_segment->range_max = scan_msg->range_max;
 
  113     scan_segment->angle_increment = scan_msg->angle_increment;
 
  114     scan_segment->time_increment = scan_msg->time_increment;
 
  115     scan_segment->scan_time = scan_msg->scan_time;
 
  118     scan_segment->angle_min = 
 
  119       scan_msg->angle_min + (scan_msg->angle_increment * r);
 
  120     scan_segment->angle_max = 
 
  121       scan_msg->angle_min + (scan_msg->angle_increment * (r + 
sizes_[i] - 1));
 
  125     scan_segment->ranges.resize(
sizes_[i]);
 
  126     memcpy(&scan_segment->ranges[0], &scan_msg->ranges[r], 
sizes_[i]*
sizeof(
int));
 
  135   std::string::size_type last_pos = str.find_first_not_of (
" ", 0);
 
  136   std::string::size_type pos = str.find_first_of (
" ", last_pos);
 
  138   while (std::string::npos != pos || std::string::npos != last_pos)
 
  140     std::string string_token = str.substr (last_pos, pos - last_pos);
 
  141     tokens.push_back (string_token);
 
  142     last_pos = str.find_first_not_of (
" ", pos);
 
  143     pos = str.find_first_of (
" ", last_pos);