logging.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 #include <string>
6 
7 // ---------------------------------------------------------------------------------------------------------------------
8 // Macros for unifying ROS1 and ROS2 logging
9 // ---------------------------------------------------------------------------------------------------------------------
10 //
11 // To print a console message, instead of using ROS_INFO(), we use RCLCPP_INFO() and its various cousins. The key
12 // difference is that RCLCPP_INFO() takes a Logger object as the first argument.
13 //
14 // ROS1
15 // http://docs.ros.org/en/noetic/api/rosconsole/html/macros__generated_8h_source.html#l00162
16 // ROS_INFO("%s", msg.data.c_str());
17 //
18 // ROS2
19 // https://docs.ros2.org/bouncy/api/rclcpp/logging_8hpp.html#a44818c8a1fd292cd0e81759e956765d7
20 // RCLCPP_INFO(node->get_logger(), "%s\n", msg.data.c_str());
21 //
22 // Non-node loggers can also be created that use a specific name.
23 // see: https://answers.ros.org/question/361542/ros-2-how-to-create-a-non-node-logger/
24 // see: https://docs.ros2.org/dashing/api/rclcpp/namespacerclcpp.html#ae7295751947c08312aa69f45fd673171
25 // --> rclcpp::get_logger("AnyLoggerName")
26 
27 // ---------------------------------------------------------------------------------------------------------------------
28 // Macros for unifying ROS1 and ROS2 logging - General
29 // ---------------------------------------------------------------------------------------------------------------------
30 
31 #define DEFAULT_LOGGER "ensenso_camera"
32 
33 // ---------------------------------------------------------------------------------------------------------------------
34 // Macros for unifying ROS1 and ROS2 logging - DEBUG
35 // ---------------------------------------------------------------------------------------------------------------------
36 
37 #ifdef ROS2 /**********************************************************************************************************/
38 #include "rclcpp/rclcpp.hpp"
39 
40 template <typename... T>
41 void ENSENSO_DEBUG(const char* arg, T... args)
42 {
43  RCLCPP_DEBUG(rclcpp::get_logger(DEFAULT_LOGGER), arg, args...);
44 }
45 
46 template <typename... T>
47 void ENSENSO_DEBUG(ensenso::ros::NodeHandle nh, const char* arg, T... args)
48 {
49  RCLCPP_DEBUG(nh->get_logging_interface()->get_logger(), arg, args...);
50 }
51 
52 template <typename... T>
53 void ENSENSO_DEBUG_NAMED(std::string name, T... args)
54 {
55  RCLCPP_DEBUG(rclcpp::get_logger(name), args...);
56 }
57 
58 template <typename... T>
59 void ENSENSO_DEBUG_ONCE(const char* arg, T... args)
60 {
61  RCLCPP_DEBUG_ONCE(rclcpp::get_logger(DEFAULT_LOGGER), arg, args...);
62 }
63 
64 template <typename... T>
65 void ENSENSO_DEBUG_ONCE(ensenso::ros::NodeHandle nh, const char* arg, T... args)
66 {
67  RCLCPP_DEBUG_ONCE(nh->get_logging_interface()->get_logger(), arg, args...);
68 }
69 
70 #else /***ROS1*********************************************************************************************************/
71 #include <ros/ros.h>
72 
73 template <typename... T>
74 void ENSENSO_DEBUG(T... args)
75 {
76  ROS_DEBUG(args...);
77 }
78 
79 template <typename... T>
81 {
82  (void)nh;
83  ROS_DEBUG(args...);
84 }
85 
86 template <typename... T>
87 void ENSENSO_DEBUG_NAMED(std::string name, T... args)
88 {
89  ROS_DEBUG_NAMED(name, args...);
90 }
91 
92 template <typename... T>
94 {
95  ROS_DEBUG_ONCE(args...);
96 }
97 
98 template <typename... T>
100 {
101  (void)nh;
102  ROS_DEBUG_ONCE(args...);
103 }
104 #endif
105 
106 // ---------------------------------------------------------------------------------------------------------------------
107 // Macros for unifying ROS1 and ROS2 logging - INFO
108 // ---------------------------------------------------------------------------------------------------------------------
109 
110 #ifdef ROS2
111 template <typename... T>
112 void ENSENSO_INFO(const char* arg, T... args)
113 {
114  RCLCPP_INFO(rclcpp::get_logger(DEFAULT_LOGGER), arg, args...);
115 }
116 
117 template <typename... T>
118 void ENSENSO_INFO(ensenso::ros::NodeHandle nh, const char* arg, T... args)
119 {
120  RCLCPP_INFO(nh->get_logging_interface()->get_logger(), arg, args...);
121 }
122 
123 template <typename... T>
124 void ENSENSO_INFO_NAMED(std::string name, T... args)
125 {
126  RCLCPP_INFO(rclcpp::get_logger(name), args...);
127 }
128 
129 template <typename... T>
130 void ENSENSO_INFO_ONCE(const char* arg, T... args)
131 {
132  RCLCPP_INFO_ONCE(rclcpp::get_logger(DEFAULT_LOGGER), arg, args...);
133 }
134 
135 template <typename... T>
136 void ENSENSO_INFO_ONCE(ensenso::ros::NodeHandle nh, const char* arg, T... args)
137 {
138  RCLCPP_INFO_ONCE(nh->get_logging_interface()->get_logger(), arg, args...);
139 }
140 #else
141 template <typename... T>
142 void ENSENSO_INFO(T... args)
143 {
144  ROS_INFO(args...);
145 }
146 
147 template <typename... T>
149 {
150  (void)nh;
151  ROS_INFO(args...);
152 }
153 
154 template <typename... T>
155 void ENSENSO_INFO_NAMED(std::string name, T... args)
156 {
157  ROS_INFO_NAMED(name, args...);
158 }
159 
160 template <typename... T>
162 {
163  ROS_INFO_ONCE(args...);
164 }
165 
166 template <typename... T>
168 {
169  (void)nh;
170  ROS_INFO_ONCE(args...);
171 }
172 #endif
173 
174 // ---------------------------------------------------------------------------------------------------------------------
175 // Macros for unifying ROS1 and ROS2 logging - WARN
176 // ---------------------------------------------------------------------------------------------------------------------
177 
178 #ifdef ROS2
179 template <typename... T>
180 void ENSENSO_WARN(const char* arg, T... args)
181 {
182  RCLCPP_WARN(rclcpp::get_logger(DEFAULT_LOGGER), arg, args...);
183 }
184 
185 template <typename... T>
186 void ENSENSO_WARN(ensenso::ros::NodeHandle nh, const char* arg, T... args)
187 {
188  RCLCPP_WARN(nh->get_logging_interface()->get_logger(), arg, args...);
189 }
190 
191 template <typename... T>
192 void ENSENSO_WARN_NAMED(std::string name, T... args)
193 {
194  RCLCPP_WARN(rclcpp::get_logger(name), args...);
195 }
196 
197 template <typename... T>
198 void ENSENSO_WARN_ONCE(const char* arg, T... args)
199 {
200  RCLCPP_WARN_ONCE(rclcpp::get_logger(DEFAULT_LOGGER), arg, args...);
201 }
202 
203 template <typename... T>
204 void ENSENSO_WARN_ONCE(ensenso::ros::NodeHandle nh, const char* arg, T... args)
205 {
206  RCLCPP_WARN_ONCE(nh->get_logging_interface()->get_logger(), arg, args...);
207 }
208 #else
209 template <typename... T>
210 void ENSENSO_WARN(T... args)
211 {
212  ROS_WARN(args...);
213 }
214 
215 template <typename... T>
217 {
218  (void)nh;
219  ROS_WARN(args...);
220 }
221 
222 template <typename... T>
223 void ENSENSO_WARN_NAMED(std::string name, T... args)
224 {
225  ROS_WARN_NAMED(name, args...);
226 }
227 
228 template <typename... T>
230 {
231  ROS_WARN_ONCE(args...);
232 }
233 
234 template <typename... T>
236 {
237  (void)nh;
238  ROS_WARN_ONCE(args...);
239 }
240 #endif
241 
242 // ---------------------------------------------------------------------------------------------------------------------
243 // Macros for unifying ROS1 and ROS2 logging - ERROR
244 // ---------------------------------------------------------------------------------------------------------------------
245 
246 #ifdef ROS2
247 template <typename... T>
248 void ENSENSO_ERROR(const char* arg, T... args)
249 {
250  RCLCPP_ERROR(rclcpp::get_logger(DEFAULT_LOGGER), arg, args...);
251 }
252 
253 template <typename... T>
254 void ENSENSO_ERROR(ensenso::ros::NodeHandle nh, const char* arg, T... args)
255 {
256  RCLCPP_ERROR(nh->get_logging_interface()->get_logger(), arg, args...);
257 }
258 
259 template <typename... T>
260 void ENSENSO_ERROR_NAMED(std::string name, T... args)
261 {
262  RCLCPP_ERROR(rclcpp::get_logger(name), args...);
263 }
264 
265 template <typename... T>
266 void ENSENSO_ERROR_ONCE(const char* arg, T... args)
267 {
268  RCLCPP_ERROR_ONCE(rclcpp::get_logger(DEFAULT_LOGGER), arg, args...);
269 }
270 
271 template <typename... T>
272 void ENSENSO_ERROR_ONCE(ensenso::ros::NodeHandle nh, const char* arg, T... args)
273 {
274  RCLCPP_ERROR_ONCE(nh->get_logging_interface()->get_logger(), arg, args...);
275 }
276 #else
277 template <typename... T>
278 void ENSENSO_ERROR(T... args)
279 {
280  ROS_ERROR(args...);
281 }
282 
283 template <typename... T>
285 {
286  (void)nh;
287  ROS_ERROR(args...);
288 }
289 
290 template <typename... T>
291 void ENSENSO_ERROR_NAMED(std::string name, T... args)
292 {
293  ROS_ERROR_NAMED(name, args...);
294 }
295 
296 template <typename... T>
298 {
299  ROS_ERROR_ONCE(args...);
300 }
301 
302 template <typename... T>
304 {
305  (void)nh;
306  ROS_ERROR_ONCE(args...);
307 }
308 #endif
void ENSENSO_WARN_ONCE(T... args)
Definition: logging.h:229
void ENSENSO_ERROR(T... args)
Definition: logging.h:278
void ENSENSO_DEBUG(T... args)
Definition: logging.h:74
#define ROS_INFO_NAMED(name,...)
void ENSENSO_INFO(T... args)
Definition: logging.h:142
#define ROS_WARN_NAMED(name,...)
#define ROS_INFO_ONCE(...)
void ENSENSO_INFO_NAMED(std::string name, T... args)
Definition: logging.h:155
#define ROS_DEBUG_ONCE(...)
void ENSENSO_ERROR_NAMED(std::string name, T... args)
Definition: logging.h:291
#define ROS_ERROR(...)
#define ROS_WARN(...)
#define DEFAULT_LOGGER
Definition: logging.h:31
#define ROS_DEBUG(...)
void ENSENSO_ERROR_ONCE(T... args)
Definition: logging.h:297
void ENSENSO_INFO_ONCE(T... args)
Definition: logging.h:161
#define ROS_DEBUG_NAMED(name,...)
#define ROS_WARN_ONCE(...)
#define ROS_INFO(...)
void ENSENSO_DEBUG_ONCE(T... args)
Definition: logging.h:93
#define ROS_ERROR_ONCE(...)
void ENSENSO_DEBUG_NAMED(std::string name, T... args)
Definition: logging.h:87
void ENSENSO_WARN_NAMED(std::string name, T... args)
Definition: logging.h:223
::ros::NodeHandle NodeHandle
Definition: node.h:214
void ENSENSO_WARN(T... args)
Definition: logging.h:210
#define ROS_ERROR_NAMED(name,...)


ensenso_camera
Author(s): Ensenso
autogenerated on Sat Jun 3 2023 02:17:04