30 #ifndef TEST_SAFETY_LIMITER_BASE_H
31 #define TEST_SAFETY_LIMITER_BASE_H
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>
46 #include <gtest/gtest.h>
50 inline void GenerateEmptyPointcloud2(sensor_msgs::PointCloud2& cloud)
54 cloud.is_bigendian =
false;
55 cloud.is_dense =
false;
57 modifier.setPointCloud2FieldsByString(1,
"xyz");
59 inline void GenerateSinglePointPointcloud2(
60 sensor_msgs::PointCloud2& cloud,
67 cloud.is_bigendian =
false;
68 cloud.is_dense =
false;
70 modifier.setPointCloud2FieldsByString(1,
"xyz");
94 inline void cbDiag(
const diagnostic_msgs::DiagnosticArray::ConstPtr& msg)
99 inline void cbStatus(
const safety_limiter_msgs::SafetyLimiterStatus::ConstPtr& msg)
104 inline void cbCmdVel(
const geometry_msgs::Twist::ConstPtr& msg)
110 diagnostic_msgs::DiagnosticArray::ConstPtr
diag_;
111 safety_limiter_msgs::SafetyLimiterStatus::ConstPtr
status_;
126 for (
int i = 0; i < 10 &&
ros::ok(); ++i)
141 std_msgs::Empty watchdog_reset;
145 const std::string frame_id,
148 sensor_msgs::PointCloud2 cloud;
149 cloud.header.frame_id = frame_id;
150 cloud.header.stamp = stamp;
151 GenerateEmptyPointcloud2(cloud);
158 const std::string frame_id,
161 sensor_msgs::PointCloud2 cloud;
162 cloud.header.frame_id = frame_id;
163 cloud.header.stamp = stamp;
164 GenerateSinglePointPointcloud2(cloud, x, y, z);
170 const float lin_y = 0.0)
172 geometry_msgs::Twist cmd_vel_out;
173 cmd_vel_out.linear.x = lin;
174 cmd_vel_out.linear.y = lin_y;
175 cmd_vel_out.angular.z = ang;
179 const std::string parent_frame_id,
180 const std::string child_frame_id,
184 geometry_msgs::TransformStamped trans;
188 trans.header.frame_id = parent_frame_id;
189 trans.child_frame_id = child_frame_id;
196 if (
diag_->status.size() == 0)
202 return static_cast<bool>(
status_);
206 #endif // TEST_SAFETY_LIMITER_BASE_H