integrationtest_ros_parameter_handler.cpp
Go to the documentation of this file.
1 // Copyright (c) 2019-2020 Pilz GmbH & Co. KG
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU Lesser General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU Lesser General Public License for more details.
12 //
13 // You should have received a copy of the GNU Lesser General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
19 #include <arpa/inet.h>
20 #include <gtest/gtest.h>
21 
22 using namespace psen_scan;
23 
24 #define DELETE_ROS_PARAM(param_name) \
25  if (ros::param::has(param_name)) \
26  { \
27  ros::param::del(param_name); \
28  }
29 
30 #define DELETE_ALL_ROS_PARAMS() \
31  DELETE_ROS_PARAM("password"); \
32  DELETE_ROS_PARAM("sensor_ip"); \
33  DELETE_ROS_PARAM("host_ip"); \
34  DELETE_ROS_PARAM("host_udp_port"); \
35  DELETE_ROS_PARAM("angle_start"); \
36  DELETE_ROS_PARAM("angle_end"); \
37  DELETE_ROS_PARAM("frame_id"); \
38  DELETE_ROS_PARAM("skip"); \
39  DELETE_ROS_PARAM("x_axis_rotation");
40 
41 namespace psen_scan_test
42 {
43 class ROSParameterHandlerTest : public ::testing::Test
44 {
45 protected:
47  : password_("ac0d68d033")
48  , host_ip_("1.2.3.5")
49  , host_udp_port_(12345)
50  , sensor_ip_("1.2.3.4")
51  , expected_password_("admin")
52  , expected_host_ip_(htobe32(inet_network(host_ip_.c_str())))
53  , expected_host_udp_port_(htole32(host_udp_port_))
54  , expected_frame_id_(DEFAULT_FRAME_ID)
55  , expected_skip_(DEFAULT_SKIP)
56  , expected_angle_start_(DEFAULT_ANGLE_START)
57  , expected_angle_end_(DEFAULT_ANGLE_END)
58  , expected_x_axis_rotation_(DEFAULT_X_AXIS_ROTATION)
59  {
61  }
62 
64 
65  // Default values to set
66  std::string password_;
67  std::string host_ip_;
69  std::string sensor_ip_;
70 
71  // Default expected values
72  std::string expected_password_;
75  std::string expected_frame_id_;
76  uint16_t expected_skip_;
80 };
81 
83 {
84 protected:
86  {
87  ros::param::set("password", password_);
88  ros::param::set("sensor_ip", sensor_ip_);
89  ros::param::set("host_ip", host_ip_);
90  ros::param::set("host_udp_port", host_udp_port_);
91  }
92 };
93 
95 {
96 protected:
98  {
99  ros::param::set("password", password_);
100  ros::param::set("host_ip", host_ip_);
101  ros::param::set("host_udp_port", host_udp_port_);
102  ros::param::set("sensor_ip", sensor_ip_);
103  ros::param::set("frame_id", DEFAULT_FRAME_ID);
104  ros::param::set("skip", DEFAULT_SKIP);
105  ros::param::set("angle_start", static_cast<double>(Degree(DEFAULT_ANGLE_START)));
106  ros::param::set("angle_end", static_cast<double>(Degree(DEFAULT_ANGLE_END)));
107  ros::param::set("x_axis_rotation", static_cast<double>(DEFAULT_X_AXIS_ROTATION));
108  }
109 };
110 
112 {
113  EXPECT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
114 }
115 
116 TEST_F(ROSRequiredParameterTest, test_required_params_only)
117 {
118  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_);
119  EXPECT_EQ(param_handler.getPassword(), expected_password_);
120  EXPECT_EQ(param_handler.getSensorIP(), sensor_ip_);
121  EXPECT_EQ(param_handler.getHostIP(), expected_host_ip_);
122  EXPECT_EQ(param_handler.getHostUDPPort(), expected_host_udp_port_);
123  EXPECT_EQ(param_handler.getFrameID(), expected_frame_id_);
124  EXPECT_EQ(param_handler.getSkip(), expected_skip_);
125  EXPECT_EQ(param_handler.getAngleStart(), expected_angle_start_);
126  EXPECT_EQ(param_handler.getAngleEnd(), expected_angle_end_);
127  EXPECT_EQ(param_handler.getXAxisRotation(), expected_x_axis_rotation_););
128 }
129 
130 TEST_F(ROSRequiredParameterTest, test_single_required_params_missing_password)
131 {
132  DELETE_ROS_PARAM("password");
133 
134  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
135 }
136 
137 TEST_F(ROSRequiredParameterTest, test_single_required_params_missing_sensor_ip)
138 {
139  DELETE_ROS_PARAM("sensor_ip");
140 
141  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
142 }
143 
144 TEST_F(ROSRequiredParameterTest, test_single_required_params_missing_host_ip)
145 {
146  DELETE_ROS_PARAM("host_ip");
147 
148  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
149 }
150 
151 TEST_F(ROSRequiredParameterTest, test_single_required_params_missing_host_udp_port)
152 {
153  DELETE_ROS_PARAM("host_udp_port");
154 
155  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
156 }
157 
159 {
160  int skip = 2;
161  std::string frame_id = "abcdefg";
162  float angle_start = 10.5;
163  float angle_end = 204.7;
164  double x_axis_rotation = 100.3;
165  ros::param::set("angle_start", angle_start);
166  ros::param::set("angle_end", angle_end);
167  ros::param::set("x_axis_rotation", x_axis_rotation);
168  ros::param::set("frame_id", frame_id);
169  ros::param::set("skip", skip);
170 
171  uint16_t expected_skip = 2;
172  PSENscanInternalAngle expected_angle_start(105);
173  PSENscanInternalAngle expected_angle_end(2047);
174  Degree expected_x_axis_rotation(x_axis_rotation);
175 
176  RosParameterHandler param_handler(node_handle_);
177  EXPECT_EQ(param_handler.getPassword(), expected_password_);
178  EXPECT_EQ(param_handler.getSensorIP(), sensor_ip_);
179  EXPECT_EQ(param_handler.getHostIP(), expected_host_ip_);
180  EXPECT_EQ(param_handler.getHostUDPPort(), expected_host_udp_port_);
181  EXPECT_EQ(param_handler.getFrameID(), frame_id);
182  EXPECT_EQ(param_handler.getSkip(), expected_skip);
183  EXPECT_EQ(param_handler.getAngleStart(), expected_angle_start);
184  EXPECT_EQ(param_handler.getAngleEnd(), expected_angle_end);
185  EXPECT_EQ(param_handler.getXAxisRotation(), expected_x_axis_rotation);
186 }
187 
188 TEST_F(ROSInvalidParameterTest, test_invalid_params_password)
189 {
190  // Set password with wrong datatype (expected string) as example for wrong datatypes on expected strings
191  ros::param::set("password", 15);
192  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
193 
194  ros::param::set("password", true);
195  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
196 
197  // Set password back to valid data type but not in accepted format
198  ros::param::set("password", "AABBCCDDEEFFGG");
199  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
200 
201  // Set password back to valid data type
202  ros::param::set("password", password_);
203  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_));
204 }
205 
206 TEST_F(ROSInvalidParameterTest, test_invalid_params_host_ip)
207 {
208  // Set host_ip with wrong datatype (expected string) as example for wrong datatypes on expected strings
209  ros::param::set("host_ip", 25);
210  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
211 
212  ros::param::set("host_ip", true);
213  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
214 
215  // Set host_ip back to valid data type but not IP-Format
216  ros::param::set("host_ip", "AABBCCDDEEFFGG");
217  // ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
218  ASSERT_ANY_THROW(RosParameterHandler param_handler(node_handle_);
219  EXPECT_EQ(static_cast<uint32_t>(0), param_handler.getHostIP()));
220 
221  // test valid
222  ros::param::set("host_ip", "1.2.3.4");
223  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_));
224 }
225 
226 TEST_F(ROSInvalidParameterTest, test_invalid_params_host_udp_port)
227 {
228  // Set host_udp_port with wrong datatype (expected int) as example for wrong datatypes on expected integers
229  ros::param::set("host_udp_port", true);
230  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
231 
232  // Wrong Datatype, but could be converted to int
233  ros::param::set("host_udp_port", "52425");
234  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
235 
236  // Wrong Datatype, but could be converted to int, but it's too large
237  ros::param::set("host_udp_port", "152425");
238  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
239 
240  // Wrong Datatype, but can't be converted to int
241  ros::param::set("host_udp_port", "AABBCCDDEEFFGG");
242  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
243 
244  // Integer too large
245  ros::param::set("host_udp_port", 150000);
246  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
247 
248  // Set negative parameter
249  ros::param::set("host_udp_port", -1);
250  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
251 
252  // test valid
253  ros::param::set("host_udp_port", 1000);
254  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_));
255 }
256 
257 TEST_F(ROSInvalidParameterTest, test_invalid_params_sensor_ip)
258 {
259  // Set sensor_ip with wrong datatype (expected string) as example for wrong datatypes on expected strings
260  ros::param::set("sensor_ip", 35);
261  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
262 
263  ros::param::set("sensor_ip", true);
264  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
265 
266  // Set sensor_ip back to valid data type, but not valid IP-Address
267  ros::param::set("sensor_ip", "AABBCCDDEEFFGG");
268  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
269 
270  // test valid
271  ros::param::set("sensor_ip", "1.2.3.4");
272  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_));
273 }
274 
275 TEST_F(ROSInvalidParameterTest, test_invalid_params_frame_id)
276 {
277  // Set frame_id with wrong datatype (expected string) as example for wrong datatypes on expected strings
278  ros::param::set("frame_id", 12);
279  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
280 
281  ros::param::set("frame_id", true);
282  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
283 
284  // Set frame_id back to valid data type, which could be interpreted as int
285  // Numbers are allowed for frame id TODO: discussion
286  ros::param::set("frame_id", "125");
287  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_));
288 }
289 
290 TEST_F(ROSInvalidParameterTest, test_invalid_params_skip)
291 {
292  // Set skip with wrong datatype (expected int) as example for wrong datatypes on expected integers
293  ros::param::set("skip", "abcde");
294  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
295 
296  ros::param::set("skip", true);
297  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
298 
299  // Wrong Datatype, but could be converted to int
300  ros::param::set("skip", "12");
301  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
302 
303  // Set skip back to valid data type, but negative
304  ros::param::set("skip", -1);
305  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
306 
307  // valid test
308  ros::param::set("skip", 0);
309  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_));
310 }
311 
312 TEST_F(ROSInvalidParameterTest, test_invalid_params_angle_start)
313 {
314  // Set angle_start with wrong datatype (expected double) as example for wrong datatypes on expected double
315  ros::param::set("angle_start", "string");
316  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
317 
318  ros::param::set("angle_start", true);
319  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
320 
321  // Wrong Datatype, but can be interpreted as int
322  ros::param::set("angle_start", "12");
323  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
324 
325  // Set angle_start back to valid data type, but too big
326  ros::param::set("angle_start", 276);
327  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
328 
329  // Set angle_start back to valid data type, but negative
330  ros::param::set("angle_start", -1);
331  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
332 
333  // valid test
334  ros::param::set("angle_start", 20.);
335  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_));
336 }
337 
338 TEST_F(ROSInvalidParameterTest, test_invalid_params_angle_end)
339 {
340  // Set angle_end with wrong datatype (expected double) as example for wrong datatypes on expected double
341  ros::param::set("angle_end", "string");
342  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
343 
344  ros::param::set("angle_end", true);
345  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
346 
347  // Wrong Datatype, but can be converted to int
348  ros::param::set("angle_end", "250");
349  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
350 
351  // Set angle_end back to valid data type, but too large
352  ros::param::set("angle_end", 276);
353  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
354 
355  // Set angle_end back to valid data type, but negative
356  ros::param::set("angle_end", -1);
357  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
358 
359  // valid test
360  ros::param::set("angle_end", 90.);
361  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_));
362 }
363 
364 TEST_F(ROSInvalidParameterTest, test_invalid_params_x_axis_rotation)
365 {
366  // Set x_axis_rotation with wrong datatype (expected double) as example for wrong datatypes on expected double
367  ros::param::set("x_axis_rotation", "string");
368  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
369 
370  ros::param::set("x_axis_rotation", true);
371  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
372 
373  // Wrong Datatype, but can be converted to float
374  ros::param::set("x_axis_rotation", "137.5");
375  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
376 
377  // Set x_axis_rotation back to valid data type, but too large
378  ros::param::set("x_axis_rotation", 361);
379  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
380 
381  // Set x_axis_rotation back to valid data type, but too small
382  ros::param::set("x_axis_rotation", -361);
383  ASSERT_THROW(RosParameterHandler param_handler(node_handle_), PSENScanFatalException);
384 
385  // valid test
386  ros::param::set("x_axis_rotation", 90.);
387  ASSERT_NO_THROW(RosParameterHandler param_handler(node_handle_));
388 }
389 } // namespace psen_scan_test
390 
391 int main(int argc, char** argv)
392 {
393  ros::init(argc, argv, "integrationtest_ros_parameter_handler");
394  ros::NodeHandle nh;
395 
396  testing::InitGoogleTest(&argc, argv);
397  return RUN_ALL_TESTS();
398 }
PSENscanInternalAngle getAngleEnd() const
Getter Method for angle_end_.
static const uint16_t DEFAULT_SKIP
TEST_F(ROSInvalidParameterTest, test_invalid_params_x_axis_rotation)
Class to model angles in degrees from user&#39;s perspective.
#define DELETE_ROS_PARAM(param_name)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static const Degree DEFAULT_X_AXIS_ROTATION(137.5)
Degree getXAxisRotation() const
Getter Method for x_axis_rotation_.
Class for getting ROS-Parameters from the parameter-server.
int main(int argc, char **argv)
PSENscanInternalAngle getAngleStart() const
Getter Method for angle_start_.
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::string getSensorIP() const
Getter Method for sensor_ip_.
uint16_t getSkip() const
Getter method for skip_.
uint32_t getHostUDPPort() const
Getter method for host_udp_port_.
uint32_t getHostIP() const
Getter method for host_ip_.
std::string getPassword() const
Getter method for password_.
static const std::string DEFAULT_FRAME_ID
std::string getFrameID() const
Getter method for frame_id_.
Class to model angles in PSENscan internal format (tenth of degrees)
static const PSENscanInternalAngle DEFAULT_ANGLE_END(2750)
static const PSENscanInternalAngle DEFAULT_ANGLE_START(0)


psen_scan
Author(s):
autogenerated on Mon Feb 28 2022 23:16:20