30 #ifndef TEST_SAFETY_LIMITER_BASE_H 31 #define TEST_SAFETY_LIMITER_BASE_H 36 #include <geometry_msgs/Twist.h> 37 #include <sensor_msgs/PointCloud2.h> 39 #include <std_msgs/Empty.h> 41 #include <gtest/gtest.h> 45 inline void GenerateSinglePointPointcloud2(
46 sensor_msgs::PointCloud2& cloud,
53 cloud.is_bigendian =
false;
54 cloud.is_dense =
false;
56 modifier.setPointCloud2FieldsByString(1,
"xyz");
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);
85 std_msgs::Empty watchdog_reset;
86 pub_watchdog_.
publish(watchdog_reset);
92 const std::string frame_id,
95 sensor_msgs::PointCloud2 cloud;
96 cloud.header.frame_id = frame_id;
97 cloud.header.stamp = stamp;
98 GenerateSinglePointPointcloud2(cloud, x, y, z);
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);
112 #endif // TEST_SAFETY_LIMITER_BASE_H ros::Publisher pub_watchdog_
void publish(const boost::shared_ptr< M > &message) const
void publishTwist(const float lin, const float ang)
ros::Publisher pub_cloud_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pub_cmd_vel_
void publishWatchdogReset()
void publishSinglePointPointcloud2(const float x, const float y, const float z, const std::string frame_id, const ros::Time stamp)