messages.hpp
Go to the documentation of this file.
1 // Copyright 2023 Ekumen, 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 #ifndef BELUGA_ROS_MESSAGES_HPP
16 #define BELUGA_ROS_MESSAGES_HPP
17 
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>
28 
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>
40 
41 #include <ros/time.h>
42 #else
43 #error BELUGA_ROS_VERSION is not defined or invalid
44 #endif
45 
46 namespace beluga_ros {
47 
49 namespace msg {
50 
51 #if BELUGA_ROS_VERSION == 2
52 
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;
58 using OccupancyGrid = nav_msgs::msg::OccupancyGrid;
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;
64 
65 #elif BELUGA_ROS_VERSION == 1
66 
67 using ColorRGBA = std_msgs::ColorRGBA;
68 using LaserScan = sensor_msgs::LaserScan;
69 using LaserScanConstSharedPtr = LaserScan::ConstPtr;
70 using Marker = visualization_msgs::Marker;
71 using MarkerArray = visualization_msgs::MarkerArray;
72 using OccupancyGrid = nav_msgs::OccupancyGrid;
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;
78 
79 #else
80 #error BELUGA_ROS_VERSION is not defined or invalid
81 #endif
82 
83 } // namespace msg
84 
85 namespace detail {
86 
87 #if BELUGA_ROS_VERSION == 2
88 
89 using Time = rclcpp::Time;
90 
91 #elif BELUGA_ROS_VERSION == 1
92 
93 using Time = ros::Time;
94 
95 #else
96 #error BELUGA_ROS_VERSION is not defined or invalid
97 #endif
98 
99 } // namespace detail
100 
102 
108 template <class Message>
109 Message& stamp_message(std::string_view frame_id, detail::Time timestamp, Message& message) {
110  message.header.frame_id = frame_id;
111  message.header.stamp = timestamp;
112  return message;
113 }
114 
116 
121 inline beluga_ros::msg::MarkerArray&
122 stamp_message(std::string_view frame_id, detail::Time timestamp, beluga_ros::msg::MarkerArray& message) {
123  for (auto& marker : message.markers) {
124  stamp_message(frame_id, timestamp, marker);
125  }
126  return message;
127 }
128 
129 } // namespace beluga_ros
130 
131 #endif // BELUGA_ROS_MESSAGES_HPP
beluga_ros::OccupancyGrid
Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.
Definition: occupancy_grid.hpp:47
time.h
beluga_ros.conversion_utils.message
message
Definition: conversion_utils.py:29
beluga_ros::stamp_message
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:109
beluga_ros::LaserScan
Thin wrapper type for 2D sensor_msgs/LaserScan messages.
Definition: laser_scan.hpp:34
ros::Time
beluga_ros
The main Beluga ROS namespace.
Definition: amcl.hpp:33


beluga_ros
Author(s):
autogenerated on Tue Jul 16 2024 03:00:02