24 #include <ignition/msgs.hh>
25 #include <ignition/transport.hh>
26 #include "../test_utils.h"
37 if (_signal == SIGINT || _signal == SIGTERM)
49 ignition::transport::Node node;
52 auto bool_pub = node.Advertise<ignition::msgs::Boolean>(
"bool");
53 ignition::msgs::Boolean bool_msg;
57 auto color_pub = node.Advertise<ignition::msgs::Color>(
"color");
58 ignition::msgs::Color color_msg;
62 auto empty_pub = node.Advertise<ignition::msgs::Empty>(
"empty");
63 ignition::msgs::Empty empty_msg;
66 auto int32_pub = node.Advertise<ignition::msgs::Int32>(
"int32");
67 ignition::msgs::Int32 int32_msg;
71 auto float_pub = node.Advertise<ignition::msgs::Float>(
"float");
72 ignition::msgs::Float float_msg;
76 auto double_pub = node.Advertise<ignition::msgs::Double>(
"double");
77 ignition::msgs::Double double_msg;
81 auto header_pub = node.Advertise<ignition::msgs::Header>(
"header");
82 ignition::msgs::Header header_msg;
86 auto string_pub = node.Advertise<ignition::msgs::StringMsg>(
"string");
87 ignition::msgs::StringMsg string_msg;
92 node.Advertise<ignition::msgs::Quaternion>(
"quaternion");
93 ignition::msgs::Quaternion quaternion_msg;
97 auto vector3_pub = node.Advertise<ignition::msgs::Vector3d>(
"vector3");
98 ignition::msgs::Vector3d vector3_msg;
102 auto clock_pub = node.Advertise<ignition::msgs::Clock>(
"clock");
103 ignition::msgs::Clock clock_msg;
107 auto point_pub = node.Advertise<ignition::msgs::Vector3d>(
"point");
108 ignition::msgs::Vector3d point_msg;
112 auto pose_pub = node.Advertise<ignition::msgs::Pose>(
"pose");
113 ignition::msgs::Pose pose_msg;
117 auto pose_stamped_pub = node.Advertise<ignition::msgs::Pose>(
"pose_stamped");
118 ignition::msgs::Pose pose_stamped_msg;
122 auto pose_v_pub = node.Advertise<ignition::msgs::Pose_V>(
"pose_array");
123 ignition::msgs::Pose_V pose_v_msg;
128 node.Advertise<ignition::msgs::Pose>(
"transform");
129 ignition::msgs::Pose transform_msg;
133 auto transform_stamped_pub =
134 node.Advertise<ignition::msgs::Pose>(
"transform_stamped");
135 ignition::msgs::Pose transform_stamped_msg;
139 auto tf2_message_pub =
140 node.Advertise<ignition::msgs::Pose_V>(
"tf2_message");
141 ignition::msgs::Pose_V tf2_msg;
145 auto image_pub = node.Advertise<ignition::msgs::Image>(
"image");
146 ignition::msgs::Image image_msg;
150 auto camera_info_pub = node.Advertise<ignition::msgs::CameraInfo>(
"camera_info");
151 ignition::msgs::CameraInfo camera_info_msg;
155 auto fluid_pressure_pub = node.Advertise<ignition::msgs::FluidPressure>(
"fluid_pressure");
156 ignition::msgs::FluidPressure fluid_pressure_msg;
160 auto imu_pub = node.Advertise<ignition::msgs::IMU>(
"imu");
161 ignition::msgs::IMU imu_msg;
165 auto laserscan_pub = node.Advertise<ignition::msgs::LaserScan>(
"laserscan");
166 ignition::msgs::LaserScan laserscan_msg;
170 auto magnetic_pub = node.Advertise<ignition::msgs::Magnetometer>(
"magnetic");
171 ignition::msgs::Magnetometer magnetometer_msg;
175 auto navsat_pub = node.Advertise<ignition::msgs::NavSat>(
"navsat");
176 ignition::msgs::NavSat navsat_msg;
180 auto actuators_pub = node.Advertise<ignition::msgs::Actuators>(
"actuators");
181 ignition::msgs::Actuators actuators_msg;
185 auto map_pub = node.Advertise<ignition::msgs::OccupancyGrid>(
"map");
186 ignition::msgs::OccupancyGrid map_msg;
190 auto odometry_pub = node.Advertise<ignition::msgs::Odometry>(
"odometry");
191 ignition::msgs::Odometry odometry_msg;
195 auto joint_states_pub = node.Advertise<ignition::msgs::Model>(
"joint_states");
196 ignition::msgs::Model joint_states_msg;
200 auto twist_pub = node.Advertise<ignition::msgs::Twist>(
"twist");
201 ignition::msgs::Twist twist_msg;
205 auto pointcloudpacked_pub = node.Advertise<ignition::msgs::PointCloudPacked>(
207 ignition::msgs::PointCloudPacked pointcloudpacked_msg;
211 auto battery_state_pub = node.Advertise<ignition::msgs::BatteryState>(
"battery_state");
212 ignition::msgs::BatteryState battery_state_msg;
215 auto marker_pub = node.Advertise<ignition::msgs::Marker>(
"marker");
216 ignition::msgs::Marker marker_msg;
219 auto marker_array_pub = node.Advertise<ignition::msgs::Marker_V>(
"marker_array");
220 ignition::msgs::Marker_V marker_array_msg;
226 bool_pub.Publish(bool_msg);
227 color_pub.Publish(color_msg);
228 empty_pub.Publish(empty_msg);
229 int32_pub.Publish(int32_msg);
230 float_pub.Publish(float_msg);
231 double_pub.Publish(double_msg);
232 header_pub.Publish(header_msg);
233 string_pub.Publish(string_msg);
234 quaternion_pub.Publish(quaternion_msg);
235 vector3_pub.Publish(vector3_msg);
236 clock_pub.Publish(clock_msg);
237 point_pub.Publish(point_msg);
238 pose_pub.Publish(pose_msg);
239 pose_v_pub.Publish(pose_v_msg);
240 pose_stamped_pub.Publish(pose_stamped_msg);
241 transform_pub.Publish(transform_msg);
242 transform_stamped_pub.Publish(transform_stamped_msg);
243 tf2_message_pub.Publish(tf2_msg);
244 image_pub.Publish(image_msg);
245 camera_info_pub.Publish(camera_info_msg);
246 fluid_pressure_pub.Publish(fluid_pressure_msg);
247 imu_pub.Publish(imu_msg);
248 laserscan_pub.Publish(laserscan_msg);
249 magnetic_pub.Publish(magnetometer_msg);
250 navsat_pub.Publish(navsat_msg);
251 actuators_pub.Publish(actuators_msg);
252 map_pub.Publish(map_msg);
253 odometry_pub.Publish(odometry_msg);
254 joint_states_pub.Publish(joint_states_msg);
255 twist_pub.Publish(twist_msg);
256 pointcloudpacked_pub.Publish(pointcloudpacked_msg);
257 battery_state_pub.Publish(battery_state_msg);
258 marker_pub.Publish(marker_msg);
259 marker_array_pub.Publish(marker_array_msg);
261 std::this_thread::sleep_for(std::chrono::milliseconds(100));