15 #ifndef BELUGA_ROS_MESSAGES_HPP
16 #define BELUGA_ROS_MESSAGES_HPP
18 #if BELUGA_ROS_VERSION == 2
19 #include <geometry_msgs/msg/point.hpp>
20 #include <geometry_msgs/msg/pose.hpp>
21 #include <geometry_msgs/msg/pose_array.hpp>
22 #include <geometry_msgs/msg/pose_with_covariance.hpp>
23 #include <geometry_msgs/msg/transform.hpp>
24 #include <nav_msgs/msg/occupancy_grid.hpp>
25 #include <sensor_msgs/msg/laser_scan.hpp>
26 #include <sensor_msgs/msg/point_cloud2.hpp>
27 #include <sensor_msgs/msg/point_field.hpp>
28 #include <sensor_msgs/point_cloud2_iterator.hpp>
29 #include <sensor_msgs/point_field_conversion.hpp>
30 #include <std_msgs/msg/color_rgba.hpp>
31 #include <visualization_msgs/msg/marker.hpp>
32 #include <visualization_msgs/msg/marker_array.hpp>
34 #include <rclcpp/time.hpp>
35 #elif BELUGA_ROS_VERSION == 1
36 #include <geometry_msgs/Point.h>
37 #include <geometry_msgs/Pose.h>
38 #include <geometry_msgs/PoseArray.h>
39 #include <geometry_msgs/PoseWithCovariance.h>
40 #include <geometry_msgs/Transform.h>
41 #include <nav_msgs/OccupancyGrid.h>
42 #include <sensor_msgs/LaserScan.h>
43 #include <sensor_msgs/PointCloud2.h>
44 #include <sensor_msgs/PointField.h>
45 #include <sensor_msgs/point_cloud2_iterator.h>
46 #include <sensor_msgs/point_field_conversion.h>
47 #include <std_msgs/ColorRGBA.h>
48 #include <visualization_msgs/Marker.h>
49 #include <visualization_msgs/MarkerArray.h>
53 #error BELUGA_ROS_VERSION is not defined or invalid
61 #if BELUGA_ROS_VERSION == 2
63 using ColorRGBA = std_msgs::msg::ColorRGBA;
64 using LaserScan = sensor_msgs::msg::LaserScan;
65 using LaserScanConstSharedPtr = LaserScan::ConstSharedPtr;
66 using PointCloud2 = sensor_msgs::msg::PointCloud2;
67 using PointCloud2ConstSharedPtr = PointCloud2::ConstSharedPtr;
68 template <
typename Scalar>
69 using PointCloud2ConstIterator = sensor_msgs::PointCloud2ConstIterator<Scalar>;
70 template <
typename Scalar>
71 using PointCloud2Iterator = sensor_msgs::PointCloud2Iterator<Scalar>;
72 using PointCloud2Modifier = sensor_msgs::PointCloud2Modifier;
73 using PointField = sensor_msgs::msg::PointField;
74 using Marker = visualization_msgs::msg::Marker;
75 using MarkerArray = visualization_msgs::msg::MarkerArray;
77 using OccupancyGridConstSharedPtr = OccupancyGrid::ConstSharedPtr;
78 using Point = geometry_msgs::msg::Point;
79 using Pose = geometry_msgs::msg::Pose;
80 using PoseArray = geometry_msgs::msg::PoseArray;
81 using PoseWithCovariance = geometry_msgs::msg::PoseWithCovariance;
82 using Transform = geometry_msgs::msg::Transform;
84 #elif BELUGA_ROS_VERSION == 1
86 using ColorRGBA = std_msgs::ColorRGBA;
88 using LaserScanConstSharedPtr = LaserScan::ConstPtr;
89 using PointCloud2 = sensor_msgs::PointCloud2;
90 using PointCloud2ConstSharedPtr = PointCloud2::ConstPtr;
91 template <
typename Scalar>
92 using PointCloud2ConstIterator = sensor_msgs::PointCloud2ConstIterator<Scalar>;
93 template <
typename Scalar>
94 using PointCloud2Iterator = sensor_msgs::PointCloud2Iterator<Scalar>;
95 using PointCloud2Modifier = sensor_msgs::PointCloud2Modifier;
96 using PointField = sensor_msgs::PointField;
97 using Marker = visualization_msgs::Marker;
98 using MarkerArray = visualization_msgs::MarkerArray;
100 using OccupancyGridConstSharedPtr = OccupancyGrid::ConstPtr;
101 using Point = geometry_msgs::Point;
102 using Pose = geometry_msgs::Pose;
103 using PoseArray = geometry_msgs::PoseArray;
104 using PoseWithCovariance = geometry_msgs::PoseWithCovariance;
105 using Transform = geometry_msgs::Transform;
108 #error BELUGA_ROS_VERSION is not defined or invalid
115 #if BELUGA_ROS_VERSION == 2
117 using Time = rclcpp::Time;
119 #elif BELUGA_ROS_VERSION == 1
121 using Time = ros::Time;
124 #error BELUGA_ROS_VERSION is not defined or invalid
136 template <
class Message>
137 Message&
stamp_message(std::string_view frame_id, detail::Time timestamp, Message& message) {
138 message.header.frame_id = frame_id;
139 message.header.stamp = timestamp;
149 inline beluga_ros::msg::MarkerArray&
150 stamp_message(std::string_view frame_id, detail::Time timestamp, beluga_ros::msg::MarkerArray& message) {
151 for (
auto& marker : message.markers) {
Thin wrapper type for 2D sensor_msgs/LaserScan messages.
Definition: laser_scan.hpp:34
Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.
Definition: occupancy_grid.hpp:47
The main Beluga ROS namespace.
Definition: amcl.hpp:44
Message & stamp_message(std::string_view frame_id, detail::Time timestamp, Message &message)
Stamp a message with a frame ID and timestamp.
Definition: messages.hpp:137