laser_scan_sparsifier.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 LaserScanSparsifier");
39 
40  // **** get paramters
41 
42  if (!nh_private_.getParam ("step", step_))
43  step_ = 2;
44 
46  "step parameter is set to %, must be > 0", step_);
47 
48  // **** advertise topics
49 
50  scan_publisher_ = nh_.advertise<sensor_msgs::LaserScan>(
51  "scan_sparse", 10);
52 
53  // **** subscribe to laser scan messages
54 
56  "scan", 10, &LaserScanSparsifier::scanCallback, this);
57 }
58 
60 {
61  ROS_INFO ("Destroying LaserScanSparsifier");
62 }
63 
64 void LaserScanSparsifier::scanCallback (const sensor_msgs::LaserScanConstPtr& scan_msg)
65 {
66  sensor_msgs::LaserScan::Ptr scan_sparse;
67  scan_sparse = boost::make_shared<sensor_msgs::LaserScan>();
68 
69  // copy over equal fields
70 
71  scan_sparse->header = scan_msg->header;
72  scan_sparse->range_min = scan_msg->range_min;
73  scan_sparse->range_max = scan_msg->range_max;
74  scan_sparse->angle_min = scan_msg->angle_min;
75  scan_sparse->angle_increment = scan_msg->angle_increment * step_;
76  scan_sparse->time_increment = scan_msg->time_increment;
77  scan_sparse->scan_time = scan_msg->scan_time;
78 
79  // determine size of new scan
80 
81  unsigned int size_sparse = scan_msg->ranges.size() / step_;
82  scan_sparse->ranges.resize(size_sparse);
83 
84  // determine new maximum angle
85 
86  scan_sparse->angle_max =
87  scan_sparse->angle_min + (scan_sparse->angle_increment * (size_sparse - 1));
88 
89  for (unsigned int i = 0; i < size_sparse; i++)
90  {
91  scan_sparse->ranges[i] = scan_msg->ranges[i * step_];
92  // TODO - also copy intensity values
93  }
94 
95  scan_publisher_.publish(scan_sparse);
96 }
97 
98 } //namespace scan_tools
99 
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
LaserScanSparsifier(ros::NodeHandle nh, ros::NodeHandle nh_private)
#define ROS_INFO(...)
#define ROS_ASSERT_MSG(cond,...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool getParam(const std::string &key, std::string &s) const
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan_msg)


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