test_safety_limiter2.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 
41 TEST_F(SafetyLimiterTest, SafetyLimitLinearSimpleSimulationWithMargin)
42 {
43  const float dt = 0.02;
44  ros::Rate wait(1.0 / dt);
45 
46  const float velocities[] =
47  {
48  -0.8, -0.4, 0.4, 0.8
49  };
50  for (const float vel : velocities)
51  {
52  float x = 0;
53  bool stop = false;
54  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
55  [dt, &x, &stop](const geometry_msgs::Twist::ConstPtr& msg) -> void
56  {
57  if (std::abs(msg->linear.x) < 1e-4 && x > 0.5)
58  stop = true;
59 
60  x += dt * msg->linear.x;
61  };
62  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
63 
64  for (int i = 0; i < lround(10.0 / dt) && ros::ok() && !stop; ++i)
65  {
66  if (vel > 0)
67  publishSinglePointPointcloud2(1.0 - x, 0, 0, "base_link", ros::Time::now());
68  else
69  publishSinglePointPointcloud2(-3.0 - x, 0, 0, "base_link", ros::Time::now());
70  publishWatchdogReset();
71  publishTwist(vel, 0.0);
72 
73  wait.sleep();
74  ros::spinOnce();
75  }
76  // margin is set to 0.2
77  if (vel > 0)
78  {
79  EXPECT_GT(0.81, x);
80  EXPECT_LT(0.75, x);
81  }
82  else
83  {
84  EXPECT_LT(-0.81, x);
85  EXPECT_GT(-0.75, x);
86  }
87  sub_cmd_vel.shutdown();
88  }
89 }
90 
91 int main(int argc, char** argv)
92 {
93  testing::InitGoogleTest(&argc, argv);
94  ros::init(argc, argv, "test_safety_limiter");
95 
96  return RUN_ALL_TESTS();
97 }
msg
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST_F(SafetyLimiterTest, SafetyLimitLinearSimpleSimulationWithMargin)
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
bool sleep()
static Time now()
ROSCPP_DECL void spinOnce()


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