test_safety_limiter_base.h
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 #ifndef TEST_SAFETY_LIMITER_BASE_H
31 #define TEST_SAFETY_LIMITER_BASE_H
32 
33 #include <string>
34 
35 #include <ros/ros.h>
36 
37 #include <diagnostic_msgs/DiagnosticArray.h>
38 #include <geometry_msgs/Twist.h>
39 #include <sensor_msgs/PointCloud2.h>
41 #include <std_msgs/Empty.h>
42 #include <safety_limiter_msgs/SafetyLimiterStatus.h>
43 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
45 
46 #include <gtest/gtest.h>
47 
48 namespace
49 {
50 inline void GenerateEmptyPointcloud2(sensor_msgs::PointCloud2& cloud)
51 {
52  cloud.height = 1;
53  cloud.width = 0;
54  cloud.is_bigendian = false;
55  cloud.is_dense = false;
56  sensor_msgs::PointCloud2Modifier modifier(cloud);
57  modifier.setPointCloud2FieldsByString(1, "xyz");
58 }
59 inline void GenerateSinglePointPointcloud2(
60  sensor_msgs::PointCloud2& cloud,
61  const float x,
62  const float y,
63  const float z)
64 {
65  cloud.height = 1;
66  cloud.width = 1;
67  cloud.is_bigendian = false;
68  cloud.is_dense = false;
69  sensor_msgs::PointCloud2Modifier modifier(cloud);
70  modifier.setPointCloud2FieldsByString(1, "xyz");
71  sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
72  sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
73  sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
74  modifier.resize(1);
75  *iter_x = x;
76  *iter_y = y;
77  *iter_z = z;
78 }
79 } // namespace
80 
81 class SafetyLimiterTest : public ::testing::Test
82 {
83 protected:
91 
93 
94  inline void cbDiag(const diagnostic_msgs::DiagnosticArray::ConstPtr& msg)
95  {
96  diag_ = msg;
97  }
98 
99  inline void cbStatus(const safety_limiter_msgs::SafetyLimiterStatus::ConstPtr& msg)
100  {
101  status_ = msg;
102  }
103 
104  inline void cbCmdVel(const geometry_msgs::Twist::ConstPtr& msg)
105  {
106  cmd_vel_ = msg;
107  }
108 
109 public:
110  diagnostic_msgs::DiagnosticArray::ConstPtr diag_;
111  safety_limiter_msgs::SafetyLimiterStatus::ConstPtr status_;
112  geometry_msgs::Twist::ConstPtr cmd_vel_;
113 
115  : nh_()
116  {
117  pub_cmd_vel_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel_in", 1);
118  pub_cloud_ = nh_.advertise<sensor_msgs::PointCloud2>("cloud", 1);
119  pub_watchdog_ = nh_.advertise<std_msgs::Empty>("watchdog_reset", 1);
120  sub_diag_ = nh_.subscribe("diagnostics", 1, &SafetyLimiterTest::cbDiag, this);
121  sub_status_ = nh_.subscribe("/safety_limiter/status", 1, &SafetyLimiterTest::cbStatus, this);
122  sub_cmd_vel_ = nh_.subscribe("cmd_vel", 1, &SafetyLimiterTest::cbCmdVel, this);
123 
124  ros::Rate wait(10.0);
125  // Skip initial state
126  for (int i = 0; i < 10 && ros::ok(); ++i)
127  {
130  broadcastTF("odom", "base_link", 0.0, 0.0);
131 
132  wait.sleep();
133  ros::spinOnce();
134  }
135  cmd_vel_.reset();
136  diag_.reset();
137  status_.reset();
138  }
139  inline void publishWatchdogReset()
140  {
141  std_msgs::Empty watchdog_reset;
142  pub_watchdog_.publish(watchdog_reset);
143  }
145  const std::string frame_id,
146  const ros::Time stamp)
147  {
148  sensor_msgs::PointCloud2 cloud;
149  cloud.header.frame_id = frame_id;
150  cloud.header.stamp = stamp;
151  GenerateEmptyPointcloud2(cloud);
152  pub_cloud_.publish(cloud);
153  }
155  const float x,
156  const float y,
157  const float z,
158  const std::string frame_id,
159  const ros::Time stamp)
160  {
161  sensor_msgs::PointCloud2 cloud;
162  cloud.header.frame_id = frame_id;
163  cloud.header.stamp = stamp;
164  GenerateSinglePointPointcloud2(cloud, x, y, z);
165  pub_cloud_.publish(cloud);
166  }
167  inline void publishTwist(
168  const float lin,
169  const float ang)
170  {
171  geometry_msgs::Twist cmd_vel_out;
172  cmd_vel_out.linear.x = lin;
173  cmd_vel_out.angular.z = ang;
174  pub_cmd_vel_.publish(cmd_vel_out);
175  }
176  inline void broadcastTF(
177  const std::string parent_frame_id,
178  const std::string child_frame_id,
179  const float lin,
180  const float ang)
181  {
182  geometry_msgs::TransformStamped trans;
183  trans.header.stamp = ros::Time::now();
184  trans.transform = tf2::toMsg(
185  tf2::Transform(tf2::Quaternion(tf2::Vector3(0, 0, 1), ang), tf2::Vector3(lin, 0, 0)));
186  trans.header.frame_id = parent_frame_id;
187  trans.child_frame_id = child_frame_id;
188  tfb_.sendTransform(trans);
189  }
190  inline bool hasDiag() const
191  {
192  if (!diag_)
193  return false;
194  if (diag_->status.size() == 0)
195  return false;
196  return true;
197  }
198  inline bool hasStatus() const
199  {
200  return static_cast<bool>(status_);
201  }
202 };
203 
204 #endif // TEST_SAFETY_LIMITER_BASE_H
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void cbDiag(const diagnostic_msgs::DiagnosticArray::ConstPtr &msg)
void cbStatus(const safety_limiter_msgs::SafetyLimiterStatus::ConstPtr &msg)
geometry_msgs::Twist::ConstPtr cmd_vel_
void publishTwist(const float lin, const float ang)
void cbCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
safety_limiter_msgs::SafetyLimiterStatus::ConstPtr status_
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void broadcastTF(const std::string parent_frame_id, const std::string child_frame_id, const float lin, const float ang)
void sendTransform(const geometry_msgs::TransformStamped &transform)
ros::Subscriber sub_cmd_vel_
bool sleep()
B toMsg(const A &a)
void wait(int seconds)
diagnostic_msgs::DiagnosticArray::ConstPtr diag_
static Time now()
ROSCPP_DECL void spinOnce()
void publishSinglePointPointcloud2(const float x, const float y, const float z, const std::string frame_id, const ros::Time stamp)
tf2_ros::TransformBroadcaster tfb_
void publishEmptyPointPointcloud2(const std::string frame_id, const ros::Time stamp)


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