test_safety_limiter.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2018, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 #include <geometry_msgs/Twist.h>
00032 #include <nav_msgs/OccupancyGrid.h>
00033 #include <nav_msgs/Path.h>
00034 #include <sensor_msgs/PointCloud2.h>
00035 #include <sensor_msgs/point_cloud2_iterator.h>
00036 #include <std_msgs/Empty.h>
00037 
00038 #include <algorithm>
00039 #include <string>
00040 
00041 #include <gtest/gtest.h>
00042 
00043 namespace
00044 {
00045 void GenerateSinglePointPointcloud2(
00046     sensor_msgs::PointCloud2& cloud,
00047     const float x,
00048     const float y,
00049     const float z)
00050 {
00051   cloud.height = 1;
00052   cloud.width = 1;
00053   cloud.is_bigendian = false;
00054   cloud.is_dense = false;
00055   sensor_msgs::PointCloud2Modifier modifier(cloud);
00056   modifier.setPointCloud2FieldsByString(1, "xyz");
00057   sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
00058   sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
00059   sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
00060   modifier.resize(1);
00061   *iter_x = x;
00062   *iter_y = y;
00063   *iter_z = z;
00064 }
00065 }  // namespace
00066 
00067 class SafetyLimiterTest : public ::testing::Test
00068 {
00069 protected:
00070   ros::NodeHandle nh_;
00071   ros::Publisher pub_cmd_vel_;
00072   ros::Publisher pub_cloud_;
00073   ros::Publisher pub_watchdog_;
00074 
00075 public:
00076   SafetyLimiterTest()
00077     : nh_()
00078   {
00079     pub_cmd_vel_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel_in", 1);
00080     pub_cloud_ = nh_.advertise<sensor_msgs::PointCloud2>("cloud", 1);
00081     pub_watchdog_ = nh_.advertise<std_msgs::Empty>("watchdog_reset", 1);
00082   }
00083   void publishWatchdogReset()
00084   {
00085     std_msgs::Empty watchdog_reset;
00086     pub_watchdog_.publish(watchdog_reset);
00087   }
00088   void publishSinglePointPointcloud2(
00089       const float x,
00090       const float y,
00091       const float z,
00092       const std::string frame_id,
00093       const ros::Time stamp)
00094   {
00095     sensor_msgs::PointCloud2 cloud;
00096     cloud.header.frame_id = frame_id;
00097     cloud.header.stamp = stamp;
00098     GenerateSinglePointPointcloud2(cloud, x, y, z);
00099     pub_cloud_.publish(cloud);
00100   }
00101   void publishTwist(
00102       const float lin,
00103       const float ang)
00104   {
00105     geometry_msgs::Twist cmd_vel_out;
00106     cmd_vel_out.linear.x = lin;
00107     cmd_vel_out.angular.z = ang;
00108     pub_cmd_vel_.publish(cmd_vel_out);
00109   }
00110 };
00111 
00112 TEST_F(SafetyLimiterTest, Timeouts)
00113 {
00114   geometry_msgs::Twist::ConstPtr cmd_vel;
00115   const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
00116       [&cmd_vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
00117   {
00118     cmd_vel = msg;
00119   };
00120   ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
00121 
00122   ros::Rate wait(10.0);
00123 
00124   for (size_t with_cloud = 0; with_cloud < 3; ++with_cloud)
00125   {
00126     for (size_t with_watchdog_reset = 0; with_watchdog_reset < 2; ++with_watchdog_reset)
00127     {
00128       ros::Duration(0.3).sleep();
00129 
00130       cmd_vel.reset();
00131       for (size_t i = 0; i < 20; ++i)
00132       {
00133         ASSERT_TRUE(ros::ok());
00134 
00135         if (with_watchdog_reset > 0)
00136           publishWatchdogReset();
00137 
00138         if (with_cloud > 0)
00139         {
00140           // cloud must have timestamp, otherwise the robot stops
00141           if (with_cloud > 1)
00142             publishSinglePointPointcloud2(1000, 1000, 0, "base_link", ros::Time::now());
00143           else
00144             publishSinglePointPointcloud2(1000, 1000, 0, "base_link", ros::Time());
00145         }
00146 
00147         const float vel = 0.1;
00148         const float ang_vel = 0.2;
00149         publishTwist(vel, ang_vel);
00150 
00151         wait.sleep();
00152         ros::spinOnce();
00153 
00154         if (i > 5 && cmd_vel)
00155         {
00156           if (with_watchdog_reset > 0 && with_cloud > 1)
00157           {
00158             ASSERT_EQ(cmd_vel->linear.x, vel);
00159             ASSERT_EQ(cmd_vel->linear.y, 0.0);
00160             ASSERT_EQ(cmd_vel->linear.z, 0.0);
00161             ASSERT_EQ(cmd_vel->angular.x, 0.0);
00162             ASSERT_EQ(cmd_vel->angular.y, 0.0);
00163             ASSERT_EQ(cmd_vel->angular.z, ang_vel);
00164           }
00165           else
00166           {
00167             ASSERT_EQ(cmd_vel->linear.x, 0.0);
00168             ASSERT_EQ(cmd_vel->linear.y, 0.0);
00169             ASSERT_EQ(cmd_vel->linear.z, 0.0);
00170             ASSERT_EQ(cmd_vel->angular.x, 0.0);
00171             ASSERT_EQ(cmd_vel->angular.y, 0.0);
00172             ASSERT_EQ(cmd_vel->angular.z, 0.0);
00173           }
00174         }
00175       }
00176     }
00177   }
00178 }
00179 
00180 TEST_F(SafetyLimiterTest, CloudBuffering)
00181 {
00182   ros::Rate wait(40.0);
00183 
00184   // Skip initial state
00185   for (size_t i = 0; i < 30 && ros::ok(); ++i)
00186   {
00187     publishSinglePointPointcloud2(0.5, 0, 0, "base_link", ros::Time::now());
00188     publishWatchdogReset();
00189 
00190     wait.sleep();
00191     ros::spinOnce();
00192   }
00193 
00194   bool received = false;
00195   bool failed = false;
00196   bool en = false;
00197   // 1.0 m/ss, obstacle at 0.5 m: limited to 1.0 m/s (t_margin: 0)
00198   const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
00199       [&received, &failed, &en](const geometry_msgs::Twist::ConstPtr& msg) -> void
00200   {
00201     if (!en)
00202       return;
00203     received = true;
00204     failed = true;
00205     ASSERT_NEAR(msg->linear.x, 1.0, 1e-1);
00206     failed = false;
00207   };
00208   ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
00209 
00210   for (size_t i = 0; i < 40 * 6 && ros::ok() && !failed; ++i)
00211   {
00212     // enable check after two cycles of safety_limiter
00213     if (i > 8)
00214       en = true;
00215     // safety_limiter: 10 hz, cloud publish: 40 hz
00216     // safety_limiter must check 4 buffered clouds
00217     // 1/3 of pointclouds have collision point
00218     if ((i % 3) == 0)
00219       publishSinglePointPointcloud2(0.5, 0, 0, "base_link", ros::Time::now());
00220     else
00221       publishSinglePointPointcloud2(10, 0, 0, "base_link", ros::Time::now());
00222 
00223     publishWatchdogReset();
00224     publishTwist(2.0, 0);
00225 
00226     wait.sleep();
00227     ros::spinOnce();
00228   }
00229   ASSERT_TRUE(received);
00230 }
00231 
00232 TEST_F(SafetyLimiterTest, SafetyLimitLinear)
00233 {
00234   ros::Rate wait(20.0);
00235 
00236   // Skip initial state
00237   for (size_t i = 0; i < 10 && ros::ok(); ++i)
00238   {
00239     publishSinglePointPointcloud2(0.5, 0, 0, "base_link", ros::Time::now());
00240     publishWatchdogReset();
00241 
00242     wait.sleep();
00243     ros::spinOnce();
00244   }
00245 
00246   for (float vel = 0.0; vel < 2.0; vel += 0.4)
00247   {
00248     // 1.0 m/ss, obstacle at 0.5 m: limited to 1.0 m/s
00249     bool received = false;
00250     bool failed = false;
00251     bool en = false;
00252     const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
00253         [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
00254     {
00255       if (!en)
00256         return;
00257       const float expected_vel = std::min<float>(vel, 1.0);
00258       received = true;
00259       failed = true;
00260       ASSERT_NEAR(msg->linear.x, expected_vel, 1e-1);
00261       failed = false;
00262     };
00263     ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
00264 
00265     for (size_t i = 0; i < 10 && ros::ok() && !failed; ++i)
00266     {
00267       if (i > 5)
00268         en = true;
00269       publishSinglePointPointcloud2(0.5, 0, 0, "base_link", ros::Time::now());
00270       publishWatchdogReset();
00271       publishTwist(vel, ((i % 5) - 2.0) * 0.01);
00272 
00273       wait.sleep();
00274       ros::spinOnce();
00275     }
00276     ASSERT_TRUE(received);
00277     sub_cmd_vel.shutdown();
00278   }
00279 }
00280 
00281 TEST_F(SafetyLimiterTest, SafetyLimitLinearBackward)
00282 {
00283   ros::Rate wait(20.0);
00284 
00285   // Skip initial state
00286   for (size_t i = 0; i < 10 && ros::ok(); ++i)
00287   {
00288     publishSinglePointPointcloud2(-2.5, 0, 0, "base_link", ros::Time::now());
00289     publishWatchdogReset();
00290 
00291     wait.sleep();
00292     ros::spinOnce();
00293   }
00294 
00295   for (float vel = 0.0; vel > -2.0; vel -= 0.4)
00296   {
00297     // 1.0 m/ss, obstacle at -2.5 m: limited to -1.0 m/s
00298     bool received = false;
00299     bool failed = false;
00300     bool en = false;
00301     const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
00302         [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
00303     {
00304       if (!en)
00305         return;
00306       const float expected_vel = std::max<float>(vel, -1.0);
00307       received = true;
00308       failed = true;
00309       ASSERT_NEAR(msg->linear.x, expected_vel, 1e-1);
00310       failed = false;
00311     };
00312     ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
00313 
00314     for (size_t i = 0; i < 10 && ros::ok() && !failed; ++i)
00315     {
00316       if (i > 5)
00317         en = true;
00318       publishSinglePointPointcloud2(-2.5, 0, 0, "base_link", ros::Time::now());
00319       publishWatchdogReset();
00320       publishTwist(vel, ((i % 5) - 2.0) * 0.01);
00321 
00322       wait.sleep();
00323       ros::spinOnce();
00324     }
00325     ASSERT_TRUE(received);
00326     sub_cmd_vel.shutdown();
00327   }
00328 }
00329 
00330 TEST_F(SafetyLimiterTest, SafetyLimitLinearEscape)
00331 {
00332   ros::Rate wait(20.0);
00333 
00334   // Skip initial state
00335   for (size_t i = 0; i < 10 && ros::ok(); ++i)
00336   {
00337     publishSinglePointPointcloud2(-0.05, 0, 0, "base_link", ros::Time::now());
00338     publishWatchdogReset();
00339 
00340     wait.sleep();
00341     ros::spinOnce();
00342   }
00343 
00344   const float vel_ref[] = { -0.2, -0.4, 0.2, 0.4 };
00345   for (const float vel : vel_ref)
00346   {
00347     // 1.0 m/ss, obstacle at -0.05 m (already in collision): escape motion must be allowed
00348     bool received = false;
00349     bool failed = false;
00350     bool en = false;
00351     const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
00352         [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
00353     {
00354       if (!en)
00355         return;
00356       received = true;
00357       failed = true;
00358       if (vel < 0)
00359         // escaping from collision must be allowed
00360         ASSERT_NEAR(msg->linear.x, vel, 1e-1);
00361       else
00362         // colliding motion must be limited
00363         ASSERT_NEAR(msg->linear.x, 0.0, 1e-1);
00364       failed = false;
00365     };
00366     ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
00367 
00368     for (size_t i = 0; i < 10 && ros::ok() && !failed; ++i)
00369     {
00370       if (i > 5)
00371         en = true;
00372       publishSinglePointPointcloud2(-0.05, 0, 0, "base_link", ros::Time::now());
00373       publishWatchdogReset();
00374       publishTwist(vel, 0.0);
00375 
00376       wait.sleep();
00377       ros::spinOnce();
00378     }
00379     ASSERT_TRUE(received);
00380     sub_cmd_vel.shutdown();
00381   }
00382 }
00383 
00384 TEST_F(SafetyLimiterTest, SafetyLimitAngular)
00385 {
00386   ros::Rate wait(20.0);
00387 
00388   // Skip initial state
00389   for (size_t i = 0; i < 10 && ros::ok(); ++i)
00390   {
00391     publishSinglePointPointcloud2(-1, -1, 0, "base_link", ros::Time::now());
00392     publishWatchdogReset();
00393 
00394     wait.sleep();
00395     ros::spinOnce();
00396   }
00397 
00398   for (float vel = 0.0; vel < M_PI; vel += M_PI / 10)
00399   {
00400     // pi/2 rad/ss, obstacle at pi/4 rad: limited to pi/2 rad/s
00401     bool received = false;
00402     bool failed = false;
00403     bool en = false;
00404     const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
00405         [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
00406     {
00407       if (!en)
00408         return;
00409       const float expected_vel = std::min<float>(vel, M_PI / 2);
00410       received = true;
00411       failed = true;
00412       ASSERT_NEAR(msg->angular.z, expected_vel, M_PI / 20);
00413       failed = false;
00414     };
00415     ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
00416 
00417     for (size_t i = 0; i < 10 && ros::ok() && !failed; ++i)
00418     {
00419       if (i > 5)
00420         en = true;
00421       publishSinglePointPointcloud2(-1, -1, 0, "base_link", ros::Time::now());
00422       publishWatchdogReset();
00423       publishTwist((i % 3) * 0.01, vel);
00424 
00425       wait.sleep();
00426       ros::spinOnce();
00427     }
00428     ASSERT_TRUE(received);
00429     sub_cmd_vel.shutdown();
00430   }
00431 }
00432 
00433 TEST_F(SafetyLimiterTest, SafetyLimitAngularEscape)
00434 {
00435   ros::Rate wait(20.0);
00436 
00437   // Skip initial state
00438   for (size_t i = 0; i < 10 && ros::ok(); ++i)
00439   {
00440     publishSinglePointPointcloud2(-1, -0.09, 0, "base_link", ros::Time::now());
00441     publishWatchdogReset();
00442 
00443     wait.sleep();
00444     ros::spinOnce();
00445   }
00446 
00447   const float vel_ref[] = { -0.2, -0.4, 0.2, 0.4 };
00448   for (const float vel : vel_ref)
00449   {
00450     // already colliding at rear-right side: only positive rotation must be allowed
00451     bool received = false;
00452     bool failed = false;
00453     bool en = false;
00454     const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
00455         [&received, &failed, &en, vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
00456     {
00457       if (!en)
00458         return;
00459       received = true;
00460       failed = true;
00461       if (vel < 0)
00462         // escaping from collision must be allowed
00463         ASSERT_NEAR(msg->angular.z, vel, 1e-1);
00464       else
00465         // colliding motion must be limited
00466         ASSERT_NEAR(msg->angular.z, 0.0, 1e-1);
00467       failed = false;
00468     };
00469     ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
00470 
00471     for (size_t i = 0; i < 10 && ros::ok() && !failed; ++i)
00472     {
00473       if (i > 5)
00474         en = true;
00475       publishSinglePointPointcloud2(-1, -0.09, 0, "base_link", ros::Time::now());
00476       publishWatchdogReset();
00477       publishTwist(0.0, vel);
00478 
00479       wait.sleep();
00480       ros::spinOnce();
00481     }
00482     ASSERT_TRUE(received);
00483     sub_cmd_vel.shutdown();
00484   }
00485 }
00486 
00487 TEST_F(SafetyLimiterTest, NoCollision)
00488 {
00489   ros::Rate wait(20.0);
00490 
00491   for (float vel = 0.0; vel < 1.0; vel += 0.2)
00492   {
00493     for (float ang_vel = 0.0; ang_vel < 1.0; ang_vel += 0.2)
00494     {
00495       bool received = false;
00496       bool failed = false;
00497       bool en = false;
00498       const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
00499           [&received, &failed, &en, vel, ang_vel](const geometry_msgs::Twist::ConstPtr& msg) -> void
00500       {
00501         failed = true;
00502         received = true;
00503         ASSERT_NEAR(msg->linear.x, vel, 1e-3);
00504         ASSERT_NEAR(msg->angular.z, ang_vel, 1e-3);
00505         failed = false;
00506       };
00507       ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
00508 
00509       for (size_t i = 0; i < 10 && ros::ok() && !failed; ++i)
00510       {
00511         if (i > 5)
00512           en = true;
00513         publishSinglePointPointcloud2(1000, 1000, 0, "base_link", ros::Time::now());
00514         publishWatchdogReset();
00515         publishTwist(vel, ang_vel);
00516 
00517         wait.sleep();
00518         ros::spinOnce();
00519       }
00520       ASSERT_TRUE(received);
00521       sub_cmd_vel.shutdown();
00522     }
00523   }
00524 }
00525 
00526 int main(int argc, char** argv)
00527 {
00528   testing::InitGoogleTest(&argc, argv);
00529   ros::init(argc, argv, "test_safety_limiter");
00530 
00531   return RUN_ALL_TESTS();
00532 }


safety_limiter
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:21