test_scan_filter_chain.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
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 Willow Garage, Inc. 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 
30 #include <gtest/gtest.h>
31 #include <filters/filter_chain.h>
32 #include <ros/ros.h>
33 #include "sensor_msgs/LaserScan.h"
34 #include <pluginlib/class_loader.h>
35 
36 
37 sensor_msgs::LaserScan gen_msg(){
38  sensor_msgs::LaserScan msg;
39 
40  float temp[] = {1.0, 0.1, 1.0, 1.0, 1.0, 9.0, 1.0, 1.0, 1.0, 2.3};
41  std::vector<float> v1 (temp, temp + sizeof(temp) / sizeof(float));
42 
43  msg.header.stamp = ros::Time::now();
44  msg.header.frame_id = "laser";
45  msg.angle_min = -.5;
46  msg.angle_max = .5;
47  msg.angle_increment = 0.1;
48  msg.time_increment = 0.1;
49  msg.scan_time = 0.1;
50  msg.range_min = 0.5;
51  msg.range_max = 1.5;
52  msg.ranges = v1;
53  msg.intensities = v1;
54 
55  return msg;
56 }
57 
61 void expect_ranges_eq(const std::vector<float> &a, const std::vector<float> &b) {
62  for( int i=0; i<10; i++) {
63  if(std::isnan(a[i])) {
64  EXPECT_TRUE(std::isnan(b[i]));
65  }
66  else {
67  EXPECT_NEAR(a[i], b[i], 1e-6);
68  }
69  }
70 }
71 
72 TEST(ScanToScanFilterChain, BadConfiguration)
73 {
74  filters::FilterChain<sensor_msgs::LaserScan> filter_chain_("sensor_msgs::LaserScan");
75 
76  try
77  {
78  filter_chain_.configure("bad_filter_chain");
79  }
81  {
82  EXPECT_FALSE(false);
83  }
84 
85  filter_chain_.clear();
86 }
87 
88 TEST(ScanToScanFilterChain, IntensityFilter)
89 {
90  sensor_msgs::LaserScan msg_in, msg_out, expected_msg;
91  float nanval = std::numeric_limits<float>::quiet_NaN();
92  float temp[] = {1.0, nanval, 1.0, 1.0, 1.0, nanval, 1.0, 1.0, 1.0, 2.3};
93  std::vector<float> v1 (temp, temp + sizeof(temp) / sizeof(float));
94  expected_msg.ranges = v1;
95  filters::FilterChain<sensor_msgs::LaserScan> filter_chain_("sensor_msgs::LaserScan");
96 
97  EXPECT_TRUE(filter_chain_.configure("intensity_filter_chain"));
98 
99  msg_in = gen_msg();
100 
101  EXPECT_TRUE(filter_chain_.update(msg_in, msg_out));
102  expect_ranges_eq(msg_out.ranges, expected_msg.ranges);
103 
104  filter_chain_.clear();
105 }
106 
108 {
109  sensor_msgs::LaserScan msg_in, msg_out, expected_msg;
110  float temp[] = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0};
111  std::vector<float> v1 (temp, temp + sizeof(temp) / sizeof(float));
112  expected_msg.ranges = v1;
113  filters::FilterChain<sensor_msgs::LaserScan> filter_chain_("sensor_msgs::LaserScan");
114 
115  EXPECT_TRUE(filter_chain_.configure("interp_filter_chain"));
116 
117  msg_in = gen_msg();
118 
119  EXPECT_TRUE(filter_chain_.update(msg_in, msg_out));
120 
121  for( int i=0; i<10; i++){
122  EXPECT_NEAR(msg_out.ranges[i],expected_msg.ranges[i],1e-6);
123  }
124 
125  filter_chain_.clear();
126 }
127 
129 {
130  sensor_msgs::LaserScan msg_in, msg_out, expected_msg;
131  float nanval = std::numeric_limits<float>::quiet_NaN();
132  float temp[] = {nanval, 0.1, nanval, 1.0, 1.0, nanval, 1.0, 1.0, 1.0, nanval};
133  std::vector<float> v1 (temp, temp + sizeof(temp) / sizeof(float));
134  expected_msg.ranges = v1;
135  filters::FilterChain<sensor_msgs::LaserScan> filter_chain_("sensor_msgs::LaserScan");
136 
137  EXPECT_TRUE(filter_chain_.configure("shadow_filter_chain"));
138 
139  msg_in = gen_msg();
140 
141  EXPECT_TRUE(filter_chain_.update(msg_in, msg_out));
142 
143  expect_ranges_eq(msg_out.ranges, expected_msg.ranges);
144 
145  filter_chain_.clear();
146 }
147 
149 {
150  sensor_msgs::LaserScan msg_in, msg_out, expected_msg;
151  float temp[] = {1.0, 0.4, 1.0, 1.0, 1.0, 6.3333, 1.0, 1.0, 1.0, 1.8667};
152  std::vector<float> v1 (temp, temp + sizeof(temp) / sizeof(float));
153  expected_msg.ranges = v1;
154  filters::FilterChain<sensor_msgs::LaserScan> filter_chain_("sensor_msgs::LaserScan");
155 
156  EXPECT_TRUE(filter_chain_.configure("array_filter_chain"));
157 
158  msg_in = gen_msg();
159 
160  EXPECT_TRUE(filter_chain_.update(msg_in, msg_out));
161  float temp2[] = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0};
162  std::vector<float> v2 (temp2, temp2 + sizeof(temp2) / sizeof(float));
163  msg_in.ranges = v2;
164  EXPECT_TRUE(filter_chain_.update(msg_in, msg_out));
165  msg_in = gen_msg();
166  EXPECT_TRUE(filter_chain_.update(msg_in, msg_out));
167 
168  for( int i=0; i<10; i++){
169  EXPECT_NEAR(msg_out.ranges[i],expected_msg.ranges[i],1e-3);
170  EXPECT_NEAR(msg_out.intensities[i],msg_in.intensities[i],1e-3);
171  }
172 
173  filter_chain_.clear();
174 }
175 
177 {
178  sensor_msgs::LaserScan msg_in, msg_out, expected_msg;
179  const float nanval = std::numeric_limits<float>::quiet_NaN();
180  const float temp[] = {1.0, nanval, 1.0, 1.0, 1.0, nanval, 1.0, 1.0, 1.0, 2.3};
181  const std::vector<float> v1 (temp, temp + sizeof(temp) / sizeof(float));
182  expected_msg.ranges = v1;
183  filters::FilterChain<sensor_msgs::LaserScan> filter_chain_("sensor_msgs::LaserScan");
184 
185  EXPECT_TRUE(filter_chain_.configure("mask_filter_chain"));
186 
187  msg_in = gen_msg();
188 
189  EXPECT_TRUE(filter_chain_.update(msg_in, msg_out));
190 
191  expect_ranges_eq(msg_out.ranges, expected_msg.ranges);
192 
193  filter_chain_.clear();
194 }
195 
196 
197 int main(int argc, char **argv){
198  testing::InitGoogleTest(&argc, argv);
199  ros::init(argc, argv, "test_scan_to_scan_filter_chain");
200  return RUN_ALL_TESTS();
201 }
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void expect_ranges_eq(const std::vector< float > &a, const std::vector< float > &b)
bool update(const T &data_in, T &data_out)
bool configure(std::string param_name, ros::NodeHandle node=ros::NodeHandle())
static Time now()
sensor_msgs::LaserScan gen_msg()
TEST(ScanToScanFilterChain, BadConfiguration)


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