angular_bounds_filter.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef LASER_SCAN_ANGULAR_BOUNDS_FILTER_H
38 #define LASER_SCAN_ANGULAR_BOUNDS_FILTER_H
39 
40 #include <filters/filter_base.hpp>
41 #include <sensor_msgs/LaserScan.h>
42 
43 namespace laser_filters
44 {
45  class LaserScanAngularBoundsFilter : public filters::FilterBase<sensor_msgs::LaserScan>
46  {
47  public:
48  double lower_angle_;
49  double upper_angle_;
50 
51  bool configure()
52  {
53  lower_angle_ = 0;
54  upper_angle_ = 0;
55 
56  if(!getParam("lower_angle", lower_angle_) || !getParam("upper_angle", upper_angle_)){
57  ROS_ERROR("Both the lower_angle and upper_angle parameters must be set to use this filter.");
58  return false;
59  }
60 
61  return true;
62  }
63 
65 
66  bool update(const sensor_msgs::LaserScan& input_scan, sensor_msgs::LaserScan& filtered_scan){
67  filtered_scan.ranges.resize(input_scan.ranges.size());
68  filtered_scan.intensities.resize(input_scan.intensities.size());
69 
70  double start_angle = input_scan.angle_min;
71  double current_angle = input_scan.angle_min;
72  ros::Time start_time = input_scan.header.stamp;
73  unsigned int count = 0;
74  //loop through the scan and truncate the beginning and the end of the scan as necessary
75  for(unsigned int i = 0; i < input_scan.ranges.size(); ++i){
76  if(input_scan.angle_increment > 0){ //if the laserscanner turns counterclockwise
77  //wait until we get to our desired starting angle
78  if(start_angle < lower_angle_){
79  start_angle += input_scan.angle_increment;
80  current_angle += input_scan.angle_increment;
81  start_time += ros::Duration(input_scan.time_increment);
82  }
83  else{
84  filtered_scan.ranges[count] = input_scan.ranges[i];
85 
86  //make sure that we don't update intensity data if its not available
87  if(input_scan.intensities.size() > i)
88  filtered_scan.intensities[count] = input_scan.intensities[i];
89 
90  count++;
91 
92  //check if we need to break out of the loop, basically if the next increment will put us over the threshold
93  if(current_angle + input_scan.angle_increment > upper_angle_){
94  break;
95  }
96  current_angle += input_scan.angle_increment;
97  }
98  }
99  else{ //the laserscanner turns clockwise
100  //wait until we get to our desired starting angle
101  if(start_angle > upper_angle_){
102  start_angle += input_scan.angle_increment;
103  current_angle += input_scan.angle_increment;
104  start_time += ros::Duration(input_scan.time_increment);
105  }
106  else{
107  filtered_scan.ranges[count] = input_scan.ranges[i];
108 
109  //make sure that we don't update intensity data if its not available
110  if(input_scan.intensities.size() > i)
111  filtered_scan.intensities[count] = input_scan.intensities[i];
112 
113  count++;
114 
115  //check if we need to break out of the loop, basically if the next increment will put us over the threshold
116  if(current_angle + input_scan.angle_increment < lower_angle_){
117  break;
118  }
119 
120  current_angle += input_scan.angle_increment;
121 
122  }
123  }
124  }
125 
126  //make sure to set all the needed fields on the filtered scan
127  filtered_scan.header.frame_id = input_scan.header.frame_id;
128  filtered_scan.header.stamp = start_time;
129  filtered_scan.angle_min = start_angle;
130  filtered_scan.angle_max = current_angle;
131  filtered_scan.angle_increment = input_scan.angle_increment;
132  filtered_scan.time_increment = input_scan.time_increment;
133  filtered_scan.scan_time = input_scan.scan_time;
134  filtered_scan.range_min = input_scan.range_min;
135  filtered_scan.range_max = input_scan.range_max;
136 
137  filtered_scan.ranges.resize(count);
138 
139  if(input_scan.intensities.size() >= count)
140  filtered_scan.intensities.resize(count);
141 
142  ROS_DEBUG("Filtered out %d points from the laser scan.", (int)input_scan.ranges.size() - (int)count);
143 
144  return true;
145 
146  }
147  };
148 };
149 #endif
filters::FilterBase
laser_filters::LaserScanAngularBoundsFilter::upper_angle_
double upper_angle_
Definition: angular_bounds_filter.h:119
filter_base.hpp
filters::FilterBase< sensor_msgs::LaserScan >::getParam
bool getParam(const std::string &name, bool &value) const
ROS_DEBUG
#define ROS_DEBUG(...)
laser_filters::LaserScanAngularBoundsFilter::configure
bool configure()
Definition: angular_bounds_filter.h:121
laser_filters::LaserScanAngularBoundsFilter::update
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan)
Definition: angular_bounds_filter.h:136
ros::Time
ROS_ERROR
#define ROS_ERROR(...)
laser_filters::LaserScanAngularBoundsFilter::~LaserScanAngularBoundsFilter
virtual ~LaserScanAngularBoundsFilter()
Definition: angular_bounds_filter.h:134
laser_filters
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
Definition: angular_bounds_filter.h:43
ros::Duration
laser_filters::LaserScanAngularBoundsFilter::lower_angle_
double lower_angle_
Definition: angular_bounds_filter.h:118
laser_filters::LaserScanAngularBoundsFilter
Definition: angular_bounds_filter.h:80


laser_filters
Author(s): Tully Foote
autogenerated on Wed Mar 27 2024 02:53:20