test_safety_limiter.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018-2019, the neonavigation authors
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 copyright holder 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 <ros/ros.h>
31 #include <geometry_msgs/Twist.h>
32 #include <sensor_msgs/PointCloud2.h>
33 
34 #include <algorithm>
35 #include <string>
36 
37 #include <gtest/gtest.h>
38 
40 
42 {
43  geometry_msgs::Twist::ConstPtr cmd_vel;
44  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
45  [&cmd_vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
46  {
47  cmd_vel = msg;
48  };
49  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
50 
51  ros::Rate wait(10.0);
52 
53  for (int with_cloud = 0; with_cloud < 3; ++with_cloud)
54  {
55  for (int with_watchdog_reset = 0; with_watchdog_reset < 2; ++with_watchdog_reset)
56  {
57  ros::Duration(0.3).sleep();
58 
59  cmd_vel.reset();
60  for (int i = 0; i < 20; ++i)
61  {
62  ASSERT_TRUE(ros::ok());
63 
64  if (with_watchdog_reset > 0)
65  publishWatchdogReset();
66 
67  if (with_cloud > 0)
68  {
69  // cloud must have timestamp, otherwise the robot stops
70  if (with_cloud > 1)
71  publishSinglePointPointcloud2(1000, 1000, 0, "base_link", ros::Time::now());
72  else
73  publishSinglePointPointcloud2(1000, 1000, 0, "base_link", ros::Time());
74  }
75 
76  const float vel = 0.1;
77  const float ang_vel = 0.2;
78  publishTwist(vel, ang_vel);
79 
80  wait.sleep();
81  ros::spinOnce();
82 
83  if (i > 5 && cmd_vel)
84  {
85  if (with_watchdog_reset > 0 && with_cloud > 1)
86  {
87  ASSERT_EQ(cmd_vel->linear.x, vel);
88  ASSERT_EQ(cmd_vel->linear.y, 0.0);
89  ASSERT_EQ(cmd_vel->linear.z, 0.0);
90  ASSERT_EQ(cmd_vel->angular.x, 0.0);
91  ASSERT_EQ(cmd_vel->angular.y, 0.0);
92  ASSERT_EQ(cmd_vel->angular.z, ang_vel);
93  }
94  else
95  {
96  ASSERT_EQ(cmd_vel->linear.x, 0.0);
97  ASSERT_EQ(cmd_vel->linear.y, 0.0);
98  ASSERT_EQ(cmd_vel->linear.z, 0.0);
99  ASSERT_EQ(cmd_vel->angular.x, 0.0);
100  ASSERT_EQ(cmd_vel->angular.y, 0.0);
101  ASSERT_EQ(cmd_vel->angular.z, 0.0);
102  }
103  }
104  }
105  }
106  }
107 }
108 
109 TEST_F(SafetyLimiterTest, CloudBuffering)
110 {
111  ros::Rate wait(60.0);
112 
113  // Skip initial state
114  for (int i = 0; i < 30 && ros::ok(); ++i)
115  {
116  publishSinglePointPointcloud2(0.5, 0, 0, "base_link", ros::Time::now());
117  publishWatchdogReset();
118 
119  wait.sleep();
120  ros::spinOnce();
121  }
122 
123  bool received = false;
124  bool failed = false;
125  bool en = false;
126  // 1.0 m/ss, obstacle at 0.5 m: limited to 1.0 m/s (t_margin: 0)
127  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
128  [&received, &failed, &en](const geometry_msgs::Twist::ConstPtr& msg) -> void
129  {
130  if (!en)
131  return;
132  received = true;
133  failed = true;
134  ASSERT_NEAR(msg->linear.x, 1.0, 1e-1);
135  failed = false;
136  };
137  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
138 
139  for (int i = 0; i < 60 * 6 && ros::ok() && !failed; ++i)
140  {
141  // enable check after two cycles of safety_limiter
142  if (i > 8)
143  en = true;
144  // safety_limiter: 15 hz, cloud publish: 60 hz
145  // safety_limiter must check 4 buffered clouds
146  // 1/3 of pointclouds have collision point
147  if ((i % 3) == 0)
148  publishSinglePointPointcloud2(0.5, 0, 0, "base_link", ros::Time::now());
149  else
150  publishSinglePointPointcloud2(10, 0, 0, "base_link", ros::Time::now());
151 
152  publishWatchdogReset();
153  publishTwist(2.0, 0);
154 
155  wait.sleep();
156  ros::spinOnce();
157  }
158  ASSERT_TRUE(received);
159 }
160 
161 TEST_F(SafetyLimiterTest, SafetyLimitLinear)
162 {
163  ros::Rate wait(20.0);
164 
165  // Skip initial state
166  for (int i = 0; i < 10 && ros::ok(); ++i)
167  {
168  publishSinglePointPointcloud2(0.5, 0, 0, "base_link", ros::Time::now());
169  publishWatchdogReset();
170 
171  wait.sleep();
172  ros::spinOnce();
173  }
174 
175  for (float vel = 0.0; vel < 2.0; vel += 0.4)
176  {
177  // 1.0 m/ss, obstacle at 0.5 m: limited to 1.0 m/s
178  bool received = false;
179  bool failed = false;
180  bool en = false;
181  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
182  [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
183  {
184  if (!en)
185  return;
186  const float expected_vel = std::min<float>(vel, 1.0);
187  received = true;
188  failed = true;
189  ASSERT_NEAR(msg->linear.x, expected_vel, 1e-1);
190  failed = false;
191  };
192  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
193 
194  for (int i = 0; i < 10 && ros::ok() && !failed; ++i)
195  {
196  if (i > 5)
197  en = true;
198  publishSinglePointPointcloud2(0.5, 0, 0, "base_link", ros::Time::now());
199  publishWatchdogReset();
200  publishTwist(vel, ((i % 5) - 2.0) * 0.01);
201 
202  wait.sleep();
203  ros::spinOnce();
204  }
205  ASSERT_TRUE(received);
206  sub_cmd_vel.shutdown();
207  }
208 }
209 
210 TEST_F(SafetyLimiterTest, SafetyLimitLinearBackward)
211 {
212  ros::Rate wait(20.0);
213 
214  // Skip initial state
215  for (int i = 0; i < 10 && ros::ok(); ++i)
216  {
217  publishSinglePointPointcloud2(-2.5, 0, 0, "base_link", ros::Time::now());
218  publishWatchdogReset();
219 
220  wait.sleep();
221  ros::spinOnce();
222  }
223 
224  for (float vel = 0.0; vel > -2.0; vel -= 0.4)
225  {
226  // 1.0 m/ss, obstacle at -2.5 m: limited to -1.0 m/s
227  bool received = false;
228  bool failed = false;
229  bool en = false;
230  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
231  [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
232  {
233  if (!en)
234  return;
235  const float expected_vel = std::max<float>(vel, -1.0);
236  received = true;
237  failed = true;
238  ASSERT_NEAR(msg->linear.x, expected_vel, 1e-1);
239  failed = false;
240  };
241  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
242 
243  for (int i = 0; i < 10 && ros::ok() && !failed; ++i)
244  {
245  if (i > 5)
246  en = true;
247  publishSinglePointPointcloud2(-2.5, 0, 0, "base_link", ros::Time::now());
248  publishWatchdogReset();
249  publishTwist(vel, ((i % 5) - 2.0) * 0.01);
250 
251  wait.sleep();
252  ros::spinOnce();
253  }
254  ASSERT_TRUE(received);
255  sub_cmd_vel.shutdown();
256  }
257 }
258 
259 TEST_F(SafetyLimiterTest, SafetyLimitLinearEscape)
260 {
261  ros::Rate wait(20.0);
262 
263  // Skip initial state
264  for (int i = 0; i < 10 && ros::ok(); ++i)
265  {
266  publishSinglePointPointcloud2(-0.05, 0, 0, "base_link", ros::Time::now());
267  publishWatchdogReset();
268 
269  wait.sleep();
270  ros::spinOnce();
271  }
272 
273  const float vel_ref[] = { -0.2, -0.4, 0.2, 0.4 };
274  for (const float vel : vel_ref)
275  {
276  // 1.0 m/ss, obstacle at -0.05 m (already in collision): escape motion must be allowed
277  bool received = false;
278  bool failed = false;
279  bool en = false;
280  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
281  [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
282  {
283  if (!en)
284  return;
285  received = true;
286  failed = true;
287  if (vel < 0)
288  // escaping from collision must be allowed
289  ASSERT_NEAR(msg->linear.x, vel, 1e-1);
290  else
291  // colliding motion must be limited
292  ASSERT_NEAR(msg->linear.x, 0.0, 1e-1);
293  failed = false;
294  };
295  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
296 
297  for (int i = 0; i < 10 && ros::ok() && !failed; ++i)
298  {
299  if (i > 5)
300  en = true;
301  publishSinglePointPointcloud2(-0.05, 0, 0, "base_link", ros::Time::now());
302  publishWatchdogReset();
303  publishTwist(vel, 0.0);
304 
305  wait.sleep();
306  ros::spinOnce();
307  }
308  ASSERT_TRUE(received);
309  sub_cmd_vel.shutdown();
310  }
311 }
312 
313 TEST_F(SafetyLimiterTest, SafetyLimitAngular)
314 {
315  ros::Rate wait(20.0);
316 
317  // Skip initial state
318  for (int i = 0; i < 10 && ros::ok(); ++i)
319  {
320  publishSinglePointPointcloud2(-1, -1, 0, "base_link", ros::Time::now());
321  publishWatchdogReset();
322 
323  wait.sleep();
324  ros::spinOnce();
325  }
326 
327  for (float vel = 0.0; vel < M_PI; vel += M_PI / 10)
328  {
329  // pi/2 rad/ss, obstacle at pi/4 rad: limited to pi/2 rad/s
330  bool received = false;
331  bool failed = false;
332  bool en = false;
333  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
334  [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
335  {
336  if (!en)
337  return;
338  const float expected_vel = std::min<float>(vel, M_PI / 2);
339  received = true;
340  failed = true;
341  ASSERT_NEAR(msg->angular.z, expected_vel, M_PI / 20);
342  failed = false;
343  };
344  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
345 
346  for (int i = 0; i < 10 && ros::ok() && !failed; ++i)
347  {
348  if (i > 5)
349  en = true;
350  publishSinglePointPointcloud2(-1, -1.1, 0, "base_link", ros::Time::now());
351  publishWatchdogReset();
352  publishTwist((i % 3) * 0.01, vel);
353 
354  wait.sleep();
355  ros::spinOnce();
356  }
357  ASSERT_TRUE(received);
358  sub_cmd_vel.shutdown();
359  }
360 }
361 
362 TEST_F(SafetyLimiterTest, SafetyLimitAngularEscape)
363 {
364  ros::Rate wait(20.0);
365 
366  // Skip initial state
367  for (int i = 0; i < 10 && ros::ok(); ++i)
368  {
369  publishSinglePointPointcloud2(-1, -0.09, 0, "base_link", ros::Time::now());
370  publishWatchdogReset();
371 
372  wait.sleep();
373  ros::spinOnce();
374  }
375 
376  const float vel_ref[] = { -0.2, -0.4, 0.2, 0.4 };
377  for (const float vel : vel_ref)
378  {
379  // already colliding at rear-right side: only positive rotation must be allowed
380  bool received = false;
381  bool failed = false;
382  bool en = false;
383  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
384  [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
385  {
386  if (!en)
387  return;
388  received = true;
389  failed = true;
390  if (vel < 0)
391  // escaping from collision must be allowed
392  ASSERT_NEAR(msg->angular.z, vel, 1e-1);
393  else
394  // colliding motion must be limited
395  ASSERT_NEAR(msg->angular.z, 0.0, 1e-1);
396  failed = false;
397  };
398  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
399 
400  for (int i = 0; i < 10 && ros::ok() && !failed; ++i)
401  {
402  if (i > 5)
403  en = true;
404  publishSinglePointPointcloud2(-1, -0.09, 0, "base_link", ros::Time::now());
405  publishWatchdogReset();
406  publishTwist(0.0, vel);
407 
408  wait.sleep();
409  ros::spinOnce();
410  }
411  ASSERT_TRUE(received);
412  sub_cmd_vel.shutdown();
413  }
414 }
415 
417 {
418  ros::Rate wait(20.0);
419 
420  for (float vel = 0.0; vel < 1.0; vel += 0.2)
421  {
422  for (float ang_vel = 0.0; ang_vel < 1.0; ang_vel += 0.2)
423  {
424  bool received = false;
425  bool failed = false;
426  bool en = false;
427  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
428  [&received, &failed, &en, vel, ang_vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
429  {
430  failed = true;
431  received = true;
432  ASSERT_NEAR(msg->linear.x, vel, 1e-3);
433  ASSERT_NEAR(msg->angular.z, ang_vel, 1e-3);
434  failed = false;
435  };
436  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
437 
438  for (int i = 0; i < 10 && ros::ok() && !failed; ++i)
439  {
440  if (i > 5)
441  en = true;
442  publishSinglePointPointcloud2(1000, 1000, 0, "base_link", ros::Time::now());
443  publishWatchdogReset();
444  publishTwist(vel, ang_vel);
445 
446  wait.sleep();
447  ros::spinOnce();
448  }
449  ASSERT_TRUE(received);
450  sub_cmd_vel.shutdown();
451  }
452  }
453 }
454 
455 TEST_F(SafetyLimiterTest, SafetyLimitLinearSimpleSimulation)
456 {
457  const float dt = 0.02;
458  ros::Rate wait(1.0 / dt);
459 
460  const float velocities[] =
461  {
462  -0.8, -0.5, 0.5, 0.8
463  };
464  for (const float vel : velocities)
465  {
466  float x = 0;
467  bool stop = false;
468  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
469  [dt, &x, &stop](const geometry_msgs::Twist::ConstPtr& msg) -> void
470  {
471  if (std::abs(msg->linear.x) < 1e-4 && x > 0.5)
472  stop = true;
473 
474  x += dt * msg->linear.x;
475  };
476  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
477 
478  for (int i = 0; i < lround(10.0 / dt) && ros::ok() && !stop; ++i)
479  {
480  if (vel > 0)
481  publishSinglePointPointcloud2(1.0 - x, 0, 0, "base_link", ros::Time::now());
482  else
483  publishSinglePointPointcloud2(-3.0 - x, 0, 0, "base_link", ros::Time::now());
484 
485  publishWatchdogReset();
486  publishTwist(vel, 0.0);
487 
488  wait.sleep();
489  ros::spinOnce();
490  }
491  if (vel > 0)
492  {
493  EXPECT_GT(1.01, x);
494  EXPECT_LT(0.95, x);
495  }
496  else
497  {
498  EXPECT_LT(-1.01, x);
499  EXPECT_GT(-0.95, x);
500  }
501  sub_cmd_vel.shutdown();
502  }
503 }
504 
505 int main(int argc, char** argv)
506 {
507  testing::InitGoogleTest(&argc, argv);
508  ros::init(argc, argv, "test_safety_limiter");
509 
510  return RUN_ALL_TESTS();
511 }
msg
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
ROSCPP_DECL bool ok()
bool sleep()
TEST_F(SafetyLimiterTest, Timeouts)
static Time now()
ROSCPP_DECL void spinOnce()


safety_limiter
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:02