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/transform.hpp>
23 #include <nav_msgs/msg/occupancy_grid.hpp>
24 #include <sensor_msgs/msg/laser_scan.hpp>
25 #include <std_msgs/msg/color_rgba.hpp>
26 #include <visualization_msgs/msg/marker.hpp>
27 #include <visualization_msgs/msg/marker_array.hpp>
29 #include <rclcpp/time.hpp>
30 #elif BELUGA_ROS_VERSION == 1
31 #include <geometry_msgs/Point.h>
32 #include <geometry_msgs/Pose.h>
33 #include <geometry_msgs/PoseArray.h>
34 #include <geometry_msgs/Transform.h>
35 #include <nav_msgs/OccupancyGrid.h>
36 #include <sensor_msgs/LaserScan.h>
37 #include <std_msgs/ColorRGBA.h>
38 #include <visualization_msgs/Marker.h>
39 #include <visualization_msgs/MarkerArray.h>
43 #error BELUGA_ROS_VERSION is not defined or invalid
51 #if BELUGA_ROS_VERSION == 2
53 using ColorRGBA = std_msgs::msg::ColorRGBA;
54 using LaserScan = sensor_msgs::msg::LaserScan;
55 using LaserScanConstSharedPtr = LaserScan::ConstSharedPtr;
56 using Marker = visualization_msgs::msg::Marker;
57 using MarkerArray = visualization_msgs::msg::MarkerArray;
59 using OccupancyGridConstSharedPtr = OccupancyGrid::ConstSharedPtr;
60 using Point = geometry_msgs::msg::Point;
61 using Pose = geometry_msgs::msg::Pose;
62 using PoseArray = geometry_msgs::msg::PoseArray;
63 using Transform = geometry_msgs::msg::Transform;
65 #elif BELUGA_ROS_VERSION == 1
67 using ColorRGBA = std_msgs::ColorRGBA;
69 using LaserScanConstSharedPtr = LaserScan::ConstPtr;
70 using Marker = visualization_msgs::Marker;
71 using MarkerArray = visualization_msgs::MarkerArray;
73 using OccupancyGridConstSharedPtr = OccupancyGrid::ConstPtr;
74 using Point = geometry_msgs::Point;
75 using Pose = geometry_msgs::Pose;
76 using PoseArray = geometry_msgs::PoseArray;
77 using Transform = geometry_msgs::Transform;
80 #error BELUGA_ROS_VERSION is not defined or invalid
87 #if BELUGA_ROS_VERSION == 2
89 using Time = rclcpp::Time;
91 #elif BELUGA_ROS_VERSION == 1
96 #error BELUGA_ROS_VERSION is not defined or invalid
108 template <
class Message>
110 message.header.frame_id = frame_id;
111 message.header.stamp = timestamp;
121 inline beluga_ros::msg::MarkerArray&
123 for (
auto& marker :
message.markers) {
131 #endif // BELUGA_ROS_MESSAGES_HPP