angular_bounds_filter_in_place.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: Kevin Hallenbeck
36 *********************************************************************/
37 #ifndef LASER_SCAN_ANGULAR_BOUNDS_FILTER_IN_PLACE_H
38 #define LASER_SCAN_ANGULAR_BOUNDS_FILTER_IN_PLACE_H
39 
40 #include <filters/filter_base.h>
41 #include <sensor_msgs/LaserScan.h>
42 
43 namespace laser_filters
44 {
45  class LaserScanAngularBoundsFilterInPlace : 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 = input_scan; //copy entire message
68 
69  double current_angle = input_scan.angle_min;
70  unsigned int count = 0;
71  //loop through the scan and remove ranges at angles between lower_angle_ and upper_angle_
72  for(unsigned int i = 0; i < input_scan.ranges.size(); ++i){
73  if((current_angle > lower_angle_) && (current_angle < upper_angle_)){
74  filtered_scan.ranges[i] = input_scan.range_max + 1.0;
75  if(i < filtered_scan.intensities.size()){
76  filtered_scan.intensities[i] = 0.0;
77  }
78  count++;
79  }
80  current_angle += input_scan.angle_increment;
81  }
82 
83  ROS_DEBUG("Filtered out %u points from the laser scan.", count);
84 
85  return true;
86 
87  }
88  };
89 };
90 #endif
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
bool getParam(const std::string &name, std::string &value)
bool update(const sensor_msgs::LaserScan &input_scan, sensor_msgs::LaserScan &filtered_scan)
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


laser_filters
Author(s): Tully Foote
autogenerated on Tue Mar 17 2020 03:40:02