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


safety_limiter
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:36