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 #include <geometry_msgs/Twist.h>
37 #include <sensor_msgs/PointCloud2.h>
39 #include <std_msgs/Empty.h>
40 
41 #include <gtest/gtest.h>
42 
43 namespace
44 {
45 inline void GenerateSinglePointPointcloud2(
46  sensor_msgs::PointCloud2& cloud,
47  const float x,
48  const float y,
49  const float z)
50 {
51  cloud.height = 1;
52  cloud.width = 1;
53  cloud.is_bigendian = false;
54  cloud.is_dense = false;
55  sensor_msgs::PointCloud2Modifier modifier(cloud);
56  modifier.setPointCloud2FieldsByString(1, "xyz");
57  sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
58  sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
59  sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
60  modifier.resize(1);
61  *iter_x = x;
62  *iter_y = y;
63  *iter_z = z;
64 }
65 } // namespace
66 
67 class SafetyLimiterTest : public ::testing::Test
68 {
69 protected:
74 
75 public:
77  : nh_()
78  {
79  pub_cmd_vel_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel_in", 1);
80  pub_cloud_ = nh_.advertise<sensor_msgs::PointCloud2>("cloud", 1);
81  pub_watchdog_ = nh_.advertise<std_msgs::Empty>("watchdog_reset", 1);
82  }
83  inline void publishWatchdogReset()
84  {
85  std_msgs::Empty watchdog_reset;
86  pub_watchdog_.publish(watchdog_reset);
87  }
89  const float x,
90  const float y,
91  const float z,
92  const std::string frame_id,
93  const ros::Time stamp)
94  {
95  sensor_msgs::PointCloud2 cloud;
96  cloud.header.frame_id = frame_id;
97  cloud.header.stamp = stamp;
98  GenerateSinglePointPointcloud2(cloud, x, y, z);
99  pub_cloud_.publish(cloud);
100  }
101  inline void publishTwist(
102  const float lin,
103  const float ang)
104  {
105  geometry_msgs::Twist cmd_vel_out;
106  cmd_vel_out.linear.x = lin;
107  cmd_vel_out.angular.z = ang;
108  pub_cmd_vel_.publish(cmd_vel_out);
109  }
110 };
111 
112 #endif // TEST_SAFETY_LIMITER_BASE_H
void publish(const boost::shared_ptr< M > &message) const
void publishTwist(const float lin, const float ang)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publishSinglePointPointcloud2(const float x, const float y, const float z, const std::string frame_id, const ros::Time stamp)


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