ign_publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #include <atomic>
19 #include <chrono>
20 #include <csignal>
21 #include <iostream>
22 #include <string>
23 #include <thread>
24 #include <ignition/msgs.hh>
25 #include <ignition/transport.hh>
26 #include "../test_utils.h"
27 
29 static std::atomic<bool> g_terminatePub(false);
30 
35 void signal_handler(int _signal)
36 {
37  if (_signal == SIGINT || _signal == SIGTERM)
38  g_terminatePub = true;
39 }
40 
42 int main(int /*argc*/, char **/*argv*/)
43 {
44  // Install a signal handler for SIGINT and SIGTERM.
45  std::signal(SIGINT, signal_handler);
46  std::signal(SIGTERM, signal_handler);
47 
48  // Create a transport node and advertise a topic.
49  ignition::transport::Node node;
50 
51  // ignition::msgs::Boolean.
52  auto bool_pub = node.Advertise<ignition::msgs::Boolean>("bool");
53  ignition::msgs::Boolean bool_msg;
55 
56  // ignition::msgs::Color.
57  auto color_pub = node.Advertise<ignition::msgs::Color>("color");
58  ignition::msgs::Color color_msg;
60 
61  // ignition::msgs::Empty.
62  auto empty_pub = node.Advertise<ignition::msgs::Empty>("empty");
63  ignition::msgs::Empty empty_msg;
64 
65  // ignition::msgs::Int32.
66  auto int32_pub = node.Advertise<ignition::msgs::Int32>("int32");
67  ignition::msgs::Int32 int32_msg;
69 
70  // ignition::msgs::Float.
71  auto float_pub = node.Advertise<ignition::msgs::Float>("float");
72  ignition::msgs::Float float_msg;
74 
75  // ignition::msgs::Double.
76  auto double_pub = node.Advertise<ignition::msgs::Double>("double");
77  ignition::msgs::Double double_msg;
79 
80  // ignition::msgs::Header.
81  auto header_pub = node.Advertise<ignition::msgs::Header>("header");
82  ignition::msgs::Header header_msg;
84 
85  // ignition::msgs::StringMsg.
86  auto string_pub = node.Advertise<ignition::msgs::StringMsg>("string");
87  ignition::msgs::StringMsg string_msg;
89 
90  // ignition::msgs::Quaternion.
91  auto quaternion_pub =
92  node.Advertise<ignition::msgs::Quaternion>("quaternion");
93  ignition::msgs::Quaternion quaternion_msg;
95 
96  // ignition::msgs::Vector3d.
97  auto vector3_pub = node.Advertise<ignition::msgs::Vector3d>("vector3");
98  ignition::msgs::Vector3d vector3_msg;
100 
101  // ignition::msgs::Clock.
102  auto clock_pub = node.Advertise<ignition::msgs::Clock>("clock");
103  ignition::msgs::Clock clock_msg;
105 
106  // ignition::msgs::Point.
107  auto point_pub = node.Advertise<ignition::msgs::Vector3d>("point");
108  ignition::msgs::Vector3d point_msg;
110 
111  // ignition::msgs::Pose.
112  auto pose_pub = node.Advertise<ignition::msgs::Pose>("pose");
113  ignition::msgs::Pose pose_msg;
115 
116  // ignition::msgs::PoseStamped.
117  auto pose_stamped_pub = node.Advertise<ignition::msgs::Pose>("pose_stamped");
118  ignition::msgs::Pose pose_stamped_msg;
119  ros_ign_bridge::testing::createTestMsg(pose_stamped_msg);
120 
121  // ignition::msgs::Pose_V.
122  auto pose_v_pub = node.Advertise<ignition::msgs::Pose_V>("pose_array");
123  ignition::msgs::Pose_V pose_v_msg;
125 
126  // ignition::msgs::Transform.
127  auto transform_pub =
128  node.Advertise<ignition::msgs::Pose>("transform");
129  ignition::msgs::Pose transform_msg;
131 
132  // ignition::msgs::TransformStamped.
133  auto transform_stamped_pub =
134  node.Advertise<ignition::msgs::Pose>("transform_stamped");
135  ignition::msgs::Pose transform_stamped_msg;
136  ros_ign_bridge::testing::createTestMsg(transform_stamped_msg);
137 
138  // ignition::msgs::Pose_V.
139  auto tf2_message_pub =
140  node.Advertise<ignition::msgs::Pose_V>("tf2_message");
141  ignition::msgs::Pose_V tf2_msg;
143 
144  // ignition::msgs::Image.
145  auto image_pub = node.Advertise<ignition::msgs::Image>("image");
146  ignition::msgs::Image image_msg;
148 
149  // ignition::msgs::CameraInfo.
150  auto camera_info_pub = node.Advertise<ignition::msgs::CameraInfo>("camera_info");
151  ignition::msgs::CameraInfo camera_info_msg;
153 
154  // ignition::msgs::FluidPressure.
155  auto fluid_pressure_pub = node.Advertise<ignition::msgs::FluidPressure>("fluid_pressure");
156  ignition::msgs::FluidPressure fluid_pressure_msg;
157  ros_ign_bridge::testing::createTestMsg(fluid_pressure_msg);
158 
159  // ignition::msgs::IMU.
160  auto imu_pub = node.Advertise<ignition::msgs::IMU>("imu");
161  ignition::msgs::IMU imu_msg;
163 
164  // ignition::msgs::LaserScan.
165  auto laserscan_pub = node.Advertise<ignition::msgs::LaserScan>("laserscan");
166  ignition::msgs::LaserScan laserscan_msg;
168 
169  // ignition::msgs::Magnetometer.
170  auto magnetic_pub = node.Advertise<ignition::msgs::Magnetometer>("magnetic");
171  ignition::msgs::Magnetometer magnetometer_msg;
172  ros_ign_bridge::testing::createTestMsg(magnetometer_msg);
173 
174  // ignition::msgs::NavSat.
175  auto navsat_pub = node.Advertise<ignition::msgs::NavSat>("navsat");
176  ignition::msgs::NavSat navsat_msg;
178 
179  // ignition::msgs::Actuators.
180  auto actuators_pub = node.Advertise<ignition::msgs::Actuators>("actuators");
181  ignition::msgs::Actuators actuators_msg;
183 
184  // ignition::msgs::OccupancyGrid
185  auto map_pub = node.Advertise<ignition::msgs::OccupancyGrid>("map");
186  ignition::msgs::OccupancyGrid map_msg;
188 
189  // ignition::msgs::Odometry.
190  auto odometry_pub = node.Advertise<ignition::msgs::Odometry>("odometry");
191  ignition::msgs::Odometry odometry_msg;
193 
194  // ignition::msgs::Model.
195  auto joint_states_pub = node.Advertise<ignition::msgs::Model>("joint_states");
196  ignition::msgs::Model joint_states_msg;
197  ros_ign_bridge::testing::createTestMsg(joint_states_msg);
198 
199  // ignition::msgs::Twist.
200  auto twist_pub = node.Advertise<ignition::msgs::Twist>("twist");
201  ignition::msgs::Twist twist_msg;
203 
204  // ignition::msgs::PointCloudPacked.
205  auto pointcloudpacked_pub = node.Advertise<ignition::msgs::PointCloudPacked>(
206  "pointcloud2");
207  ignition::msgs::PointCloudPacked pointcloudpacked_msg;
208  ros_ign_bridge::testing::createTestMsg(pointcloudpacked_msg);
209 
210  // ignition::msgs::BatteryState.
211  auto battery_state_pub = node.Advertise<ignition::msgs::BatteryState>("battery_state");
212  ignition::msgs::BatteryState battery_state_msg;
213  ros_ign_bridge::testing::createTestMsg(battery_state_msg);
214 
215  auto marker_pub = node.Advertise<ignition::msgs::Marker>("marker");
216  ignition::msgs::Marker marker_msg;
218 
219  auto marker_array_pub = node.Advertise<ignition::msgs::Marker_V>("marker_array");
220  ignition::msgs::Marker_V marker_array_msg;
221  ros_ign_bridge::testing::createTestMsg(marker_array_msg);
222 
223  // Publish messages at 1Hz.
224  while (!g_terminatePub)
225  {
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);
260 
261  std::this_thread::sleep_for(std::chrono::milliseconds(100));
262  }
263 
264  return 0;
265 }
signal_handler
void signal_handler(int _signal)
Function callback executed when a SIGINT or SIGTERM signals are captured. This is used to break the i...
Definition: ign_publisher.cpp:35
main
int main(int, char **)
Definition: ign_publisher.cpp:42
ros_ign_bridge::testing::createTestMsg
void createTestMsg(std_msgs::Bool &_msg)
ROS test utils.
Definition: test_utils.h:120
g_terminatePub
static std::atomic< bool > g_terminatePub(false)
Flag used to break the publisher loop and terminate the program.


ros_ign_bridge
Author(s):
autogenerated on Sat Mar 11 2023 04:02:16