ros_publisher.cpp
Go to the documentation of this file.
1 // Copyright 2018 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <thread>
16 
17 #include <ros/ros.h>
18 #include <std_msgs/Bool.h>
19 #include <std_msgs/ColorRGBA.h>
20 #include <std_msgs/Float32.h>
21 #include <std_msgs/Float64.h>
22 #include <std_msgs/Header.h>
23 #include <std_msgs/Int32.h>
24 #include <std_msgs/String.h>
25 #include <geometry_msgs/Quaternion.h>
26 #include <geometry_msgs/Vector3.h>
27 #include <rosgraph_msgs/Clock.h>
28 #include <geometry_msgs/Pose.h>
29 #include <geometry_msgs/PoseArray.h>
30 #include <geometry_msgs/PoseStamped.h>
31 #include <geometry_msgs/Transform.h>
32 #include <geometry_msgs/TransformStamped.h>
33 #include <geometry_msgs/Twist.h>
34 // #include <mav_msgs/Actuators.h>
35 #include <nav_msgs/OccupancyGrid.h>
36 #include <nav_msgs/Odometry.h>
37 #include <sensor_msgs/BatteryState.h>
38 #include <sensor_msgs/CameraInfo.h>
39 #include <sensor_msgs/FluidPressure.h>
40 #include <sensor_msgs/Image.h>
41 #include <sensor_msgs/Imu.h>
42 #include <sensor_msgs/JointState.h>
43 #include <sensor_msgs/LaserScan.h>
44 #include <sensor_msgs/MagneticField.h>
45 #include <sensor_msgs/NavSatFix.h>
46 #include <sensor_msgs/PointCloud2.h>
47 #include <tf2_msgs/TFMessage.h>
48 #include <visualization_msgs/Marker.h>
49 #include <visualization_msgs/MarkerArray.h>
50 #include "../test_utils.h"
51 
53 int main(int argc, char ** argv)
54 {
55  ros::init(argc, argv, "ros_string_publisher");
57  ros::Rate loop_rate(1);
58 
59  // std_msgs::Bool.
60  ros::Publisher bool_pub = n.advertise<std_msgs::Bool>("bool", 1000);
61  std_msgs::Bool bool_msg;
63 
64  // std_msgs::ColorRGBA.
65  ros::Publisher color_pub = n.advertise<std_msgs::ColorRGBA>("color", 1000);
66  std_msgs::ColorRGBA color_msg;
68 
69  // std_msgs::Empty.
70  ros::Publisher empty_pub = n.advertise<std_msgs::Empty>("empty", 1000);
71  std_msgs::Empty empty_msg;
72 
73  // std_msgs::Int32.
74  ros::Publisher int32_pub = n.advertise<std_msgs::Int32>("int32", 1000);
75  std_msgs::Int32 int32_msg;
77 
78  // std_msgs::Float32.
79  ros::Publisher float_pub = n.advertise<std_msgs::Float32>("float", 1000);
80  std_msgs::Float32 float_msg;
82 
83  // std_msgs::Float64.
84  ros::Publisher double_pub = n.advertise<std_msgs::Float64>("double", 1000);
85  std_msgs::Float64 double_msg;
87 
88  // std_msgs::Header.
89  ros::Publisher header_pub = n.advertise<std_msgs::Header>("header", 1000);
90  std_msgs::Header header_msg;
92 
93  // std_msgs::String.
94  ros::Publisher string_pub = n.advertise<std_msgs::String>("string", 1000);
95  std_msgs::String string_msg;
97 
98  // geometry_msgs::Quaternion.
99  ros::Publisher quaternion_pub =
100  n.advertise<geometry_msgs::Quaternion>("quaternion", 1000);
101  geometry_msgs::Quaternion quaternion_msg;
103 
104  // geometry_msgs::Vector3.
105  ros::Publisher vector3_pub =
106  n.advertise<geometry_msgs::Vector3>("vector3", 1000);
107  geometry_msgs::Vector3 vector3_msg;
109 
110  // sensor_msgs::Clock.
111  ros::Publisher clock_pub =
112  n.advertise<rosgraph_msgs::Clock>("clock", 1000);
113  rosgraph_msgs::Clock clock_msg;
115 
116  // geometry_msgs::Point.
117  ros::Publisher point_pub =
118  n.advertise<geometry_msgs::Point>("point", 1000);
119  geometry_msgs::Point point_msg;
121 
122  // geometry_msgs::Pose.
123  ros::Publisher pose_pub =
124  n.advertise<geometry_msgs::Pose>("pose", 1000);
125  geometry_msgs::Pose pose_msg;
127 
128  // geometry_msgs::PoseArray.
129  ros::Publisher pose_array_pub =
130  n.advertise<geometry_msgs::PoseArray>("pose_array", 1000);
131  geometry_msgs::PoseArray pose_array_msg;
133 
134  // geometry_msgs::PoseStamped.
135  ros::Publisher pose_stamped_pub =
136  n.advertise<geometry_msgs::PoseStamped>("pose_stamped", 1000);
137  geometry_msgs::PoseStamped pose_stamped_msg;
138  ros_ign_bridge::testing::createTestMsg(pose_stamped_msg);
139 
140  // geometry_msgs::Transform.
141  ros::Publisher transform_pub =
142  n.advertise<geometry_msgs::Transform>("transform", 1000);
143  geometry_msgs::Transform transform_msg;
145 
146  // geometry_msgs::TransformStamped.
147  ros::Publisher transform_stamped_pub =
148  n.advertise<geometry_msgs::TransformStamped>("transform_stamped", 1000);
149  geometry_msgs::TransformStamped transform_stamped_msg;
150  ros_ign_bridge::testing::createTestMsg(transform_stamped_msg);
151 
152  // tf2_msgs::TFMessage.
153  ros::Publisher tf2_message_pub =
154  n.advertise<tf2_msgs::TFMessage>("tf2_message", 1000);
155  tf2_msgs::TFMessage tf2_msg;
157 
158  // geometry_msgs::Twist.
159  ros::Publisher twist_pub =
160  n.advertise<geometry_msgs::Twist>("twist", 1000);
161  geometry_msgs::Twist twist_msg;
163 
164  // mav_msgs::Actuators.
165 // ros::Publisher actuators_pub =
166 // n.advertise<mav_msgs::Actuators>("actuators", 1000);
167 // mav_msgs::Actuators actuators_msg;
168 // ros_ign_bridge::testing::createTestMsg(actuators_msg);
169 
170  // nav_msgs::OccupancyGrid.
171  ros::Publisher map_pub =
172  n.advertise<nav_msgs::OccupancyGrid>("map", 1000);
173  nav_msgs::OccupancyGrid map_msg;
175 
176  // nav_msgs::Odometry.
177  ros::Publisher odometry_pub =
178  n.advertise<nav_msgs::Odometry>("odometry", 1000);
179  nav_msgs::Odometry odometry_msg;
181 
182  // sensor_msgs::Image.
183  ros::Publisher image_pub =
184  n.advertise<sensor_msgs::Image>("image", 1000);
185  sensor_msgs::Image image_msg;
187 
188  // sensor_msgs::CameraInfo.
189  ros::Publisher camera_info_pub =
190  n.advertise<sensor_msgs::CameraInfo>("camera_info", 1000);
191  sensor_msgs::CameraInfo camera_info_msg;
193 
194  // sensor_msgs::FluidPressure.
195  ros::Publisher fluid_pressure_pub =
196  n.advertise<sensor_msgs::FluidPressure>("fluid_pressure", 1000);
197  sensor_msgs::FluidPressure fluid_pressure_msg;
198  ros_ign_bridge::testing::createTestMsg(fluid_pressure_msg);
199 
200  // sensor_msgs::Imu.
201  ros::Publisher imu_pub =
202  n.advertise<sensor_msgs::Imu>("imu", 1000);
203  sensor_msgs::Imu imu_msg;
205 
206  // sensor_msgs::JointState.
207  ros::Publisher joint_states_pub =
208  n.advertise<sensor_msgs::JointState>("joint_states", 1000);
209  sensor_msgs::JointState joint_states_msg;
210  ros_ign_bridge::testing::createTestMsg(joint_states_msg);
211 
212  // sensor_msgs::LaserScan.
213  ros::Publisher laserscan_pub =
214  n.advertise<sensor_msgs::LaserScan>("laserscan", 1000);
215  sensor_msgs::LaserScan laserscan_msg;
217 
218  // sensor_msgs::MagneticField.
219  ros::Publisher magnetic_pub =
220  n.advertise<sensor_msgs::MagneticField>("magnetic", 1000);
221  sensor_msgs::MagneticField magnetic_msg;
223 
224  // sensor_msgs::NavSatFix.
225  ros::Publisher navsat_pub =
226  n.advertise<sensor_msgs::NavSatFix>("navsat", 1000);
227  sensor_msgs::NavSatFix navsat_msg;
229 
230  // sensor_msgs::PointCloud2.
231  ros::Publisher pointcloud2_pub =
232  n.advertise<sensor_msgs::PointCloud2>("pointcloud2", 1000);
233  sensor_msgs::PointCloud2 pointcloud2_msg;
235 
236  // sensor_msgs::BatteryState.
237  ros::Publisher battery_state_pub =
238  n.advertise<sensor_msgs::BatteryState>("battery_state", 1000);
239  sensor_msgs::BatteryState battery_state_msg;
240  ros_ign_bridge::testing::createTestMsg(battery_state_msg);
241 
242  // visualization_msgs::Marker.
243  ros::Publisher marker_pub =
244  n.advertise<visualization_msgs::Marker>("marker", 1000);
245  visualization_msgs::Marker marker_msg;
247 
248  // visualization_msgs::MarkerArray.
249  ros::Publisher marker_array_pub =
250  n.advertise<visualization_msgs::MarkerArray>("marker_array", 1000);
251  visualization_msgs::MarkerArray marker_array_msg;
252  ros_ign_bridge::testing::createTestMsg(marker_array_msg);
253 
254  while (ros::ok())
255  {
256  // Publish all messages.
257  bool_pub.publish(bool_msg);
258  color_pub.publish(color_msg);
259  empty_pub.publish(empty_msg);
260  int32_pub.publish(int32_msg);
261  float_pub.publish(float_msg);
262  double_pub.publish(double_msg);
263  header_pub.publish(header_msg);
264  string_pub.publish(string_msg);
265  quaternion_pub.publish(quaternion_msg);
266  vector3_pub.publish(vector3_msg);
267  clock_pub.publish(clock_msg);
268  point_pub.publish(point_msg);
269  pose_pub.publish(pose_msg);
270  pose_array_pub.publish(pose_array_msg);
271  pose_stamped_pub.publish(pose_stamped_msg);
272  transform_pub.publish(transform_msg);
273  transform_stamped_pub.publish(transform_stamped_msg);
274  tf2_message_pub.publish(tf2_msg);
275  twist_pub.publish(twist_msg);
276  // actuators_pub.publish(actuators_msg);
277  map_pub.publish(map_msg);
278  odometry_pub.publish(odometry_msg);
279  image_pub.publish(image_msg);
280  camera_info_pub.publish(camera_info_msg);
281  fluid_pressure_pub.publish(fluid_pressure_msg);
282  imu_pub.publish(imu_msg);
283  laserscan_pub.publish(laserscan_msg);
284  magnetic_pub.publish(magnetic_msg);
285  navsat_pub.publish(navsat_msg);
286  joint_states_pub.publish(joint_states_msg);
287  pointcloud2_pub.publish(pointcloud2_msg);
288  battery_state_pub.publish(battery_state_msg);
289  marker_pub.publish(marker_msg);
290  marker_array_pub.publish(marker_array_msg);
291 
292  ros::spinOnce();
293  loop_rate.sleep();
294  }
295 
296  return 0;
297 }
main
int main(int argc, char **argv)
Definition: ros_publisher.cpp:53
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
ros_ign_bridge::testing::createTestMsg
void createTestMsg(std_msgs::Bool &_msg)
ROS test utils.
Definition: test_utils.h:120
ros::Rate::sleep
bool sleep()
ros::Rate
ros::NodeHandle


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