laser_scan_splitter.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Ivan Dryanovski, William Morris
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the CCNY Robotics Lab nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
31 
32 namespace scan_tools {
33 
35  nh_(nh),
36  nh_private_(nh_private)
37 {
38  ROS_INFO ("Starting LaserScanSplitter");
39 
40  // **** get paramters
41 
42  std::string topics_string;
43  std::string frames_string;
44  std::string sizes_string;
45 
46  if (!nh_private_.getParam ("topics", topics_string))
47  topics_string = "scan1 scan2";
48  if (!nh_private_.getParam ("frames", frames_string))
49  frames_string = "laser laser";
50  if (!nh_private_.getParam ("sizes", sizes_string))
51  sizes_string = "256 256";
52 
53  // **** tokenize inputs
54  tokenize (topics_string, published_scan_topics_);
55  tokenize (frames_string, published_laser_frames_);
56 
57  std::vector<std::string> sizes_tokens;
58  tokenize (sizes_string, sizes_tokens);
59 
60  size_sum_ = 0;
61  for (unsigned int i = 0; i < sizes_tokens.size (); i++)
62  {
63  sizes_.push_back (atoi (sizes_tokens[i].c_str ()));
64  size_sum_ += sizes_[i];
65 
66  ROS_ASSERT_MSG ((sizes_[i] > 0), "LaserScanSplitter: Scan size cannot be zero. Quitting.");
67  }
68 
69  // **** check that topic, frames, and sizes vectors have same sizes
70 
72  (sizes_.size () == published_laser_frames_.size ()),
73  "LaserScanSplitter: Invalid parameters. Quitting.");
74 
75  // **** subscribe to laser scan messages
77 
78  // **** advertise topics
79  for (unsigned int i = 0; i < published_scan_topics_.size (); i++)
80  {
81  scan_publishers_.push_back (ros::Publisher ());
82  scan_publishers_[i] =
83  nh_.advertise<sensor_msgs::LaserScan>(published_scan_topics_[i], 10);
84  }
85 }
86 
88 {
89  ROS_INFO ("Destroying LaserScanSplitter");
90 }
91 
92 void LaserScanSplitter::scanCallback (const sensor_msgs::LaserScanConstPtr & scan_msg)
93 {
94  // **** check for scan size
95  if (size_sum_ != scan_msg->ranges.size ())
96  {
97  ROS_WARN ("LaserScanSplitter: Received a laser scan with size (%d) \
98  incompatible to input parameters. Skipping scan.", (int)scan_msg->ranges.size());
99  return;
100  }
101 
102  // **** copy information over
103  int r = 0;
104 
105  for (unsigned int i = 0; i < published_scan_topics_.size (); i++)
106  {
107  sensor_msgs::LaserScan::Ptr scan_segment;
108  scan_segment = boost::make_shared<sensor_msgs::LaserScan>();
109 
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;
116  scan_segment->header.frame_id = published_laser_frames_[i];
117 
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));
122 
123  // TODO - also copy intensity values
124 
125  scan_segment->ranges.resize(sizes_[i]);
126  memcpy(&scan_segment->ranges[0], &scan_msg->ranges[r], sizes_[i]*sizeof(int));
127  r+=sizes_[i];
128 
129  scan_publishers_[i].publish (scan_segment);
130  }
131 }
132 
133 void LaserScanSplitter::tokenize (const std::string & str, std::vector < std::string > &tokens)
134 {
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);
137 
138  while (std::string::npos != pos || std::string::npos != last_pos)
139  {
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);
144  }
145 }
146 
147 } //namespace scan_tools
148 
void tokenize(const std::string &str, std::vector< std::string > &tokens)
std::vector< ros::Publisher > scan_publishers_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
const std::string scan_topic_
#define ROS_WARN(...)
std::vector< std::string > published_laser_frames_
#define ROS_INFO(...)
#define ROS_ASSERT_MSG(cond,...)
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan_msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool getParam(const std::string &key, std::string &s) const
std::vector< std::string > published_scan_topics_
LaserScanSplitter(ros::NodeHandle nh, ros::NodeHandle nh_private)


laser_scan_splitter
Author(s): Ivan Dryanovski, William Morris
autogenerated on Mon Jun 10 2019 15:08:44