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 <algorithm>
31 #include <cmath>
32 #include <string>
33 
34 #include <ros/ros.h>
35 
36 #include <geometry_msgs/Twist.h>
37 #include <sensor_msgs/PointCloud2.h>
38 
40 
41 #include <gtest/gtest.h>
42 
43 TEST_F(SafetyLimiterTest, SafetyLimitLinearSimpleSimulationWithMargin)
44 {
45  const float dt = 0.02;
46  const double ax = 2.0; // [m/ss]
47  double v = 0.0; // [m/s]
48  ros::Rate wait(1.0 / dt);
49 
50  const float velocities[] = {-0.8, -0.4, 0.4, 0.8};
51  for (const float vel : velocities)
52  {
53  float x = 0;
54  bool stopped = false;
55  const boost::function<void(const geometry_msgs::Twist::ConstPtr&)> cb_cmd_vel =
56  [dt, ax, &x, &v, &stopped](const geometry_msgs::Twist::ConstPtr& msg) -> void
57  {
58  if (msg->linear.x >= v)
59  {
60  v = std::min(v + ax * dt, msg->linear.x);
61  }
62  else
63  {
64  v = std::max(v - ax * dt, msg->linear.x);
65  }
66  x += dt * v;
67 
68  if (std::abs(v) < 1e-4 && std::abs(x) > 0.5)
69  {
70  stopped = true;
71  }
72  };
73  ros::Subscriber sub_cmd_vel = nh_.subscribe("cmd_vel", 1, cb_cmd_vel);
74 
75  int count_after_stop = 10;
76  for (float t = 0; t < 10.0 && ros::ok() && count_after_stop > 0; t += dt)
77  {
78  if (vel > 0)
79  publishSinglePointPointcloud2(1.5 - x, 0, 0, "base_link", ros::Time::now());
80  else
81  publishSinglePointPointcloud2(-3.5 - x, 0, 0, "base_link", ros::Time::now());
82  publishWatchdogReset();
83  publishTwist(vel, 0.0);
84  broadcastTF("odom", "base_link", x, 0.0);
85 
86  wait.sleep();
87  ros::spinOnce();
88  if (stopped)
89  {
90  count_after_stop--;
91  }
92  }
93  // margin is set to 0.2
94  if (vel > 0)
95  {
96  EXPECT_GT(1.4, x)
97  << "vel: " << vel; // Collision point - margin
98  EXPECT_LT(1.3, x)
99  << "vel: " << vel; // Collision point - margin * 2
100  }
101  else
102  {
103  EXPECT_LT(-1.4, x)
104  << "vel: " << vel; // Collision point + margin
105  EXPECT_GT(-1.3, x)
106  << "vel: " << vel; // Collision point + margin * 2
107  }
108  sub_cmd_vel.shutdown();
109  }
110 }
111 
112 int main(int argc, char** argv)
113 {
114  testing::InitGoogleTest(&argc, argv);
115  ros::init(argc, argv, "test_safety_limiter");
116 
117  return RUN_ALL_TESTS();
118 }
msg
msg
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
test_safety_limiter_base.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
main
int main(int argc, char **argv)
Definition: test_safety_limiter2.cpp:112
ros::Subscriber::shutdown
void shutdown()
wait
void wait(int seconds)
ros::ok
ROSCPP_DECL bool ok()
ros::Rate
TEST_F
TEST_F(SafetyLimiterTest, SafetyLimitLinearSimpleSimulationWithMargin)
Definition: test_safety_limiter2.cpp:43
SafetyLimiterTest
Definition: test_safety_limiter_base.h:81
ros::Subscriber
ros::Time::now
static Time now()


safety_limiter
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:16