ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
logging_rosout.c
1 // Copyright 2018-2019 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 "rcl/allocator.h"
16 #include "rcl/error_handling.h"
17 #include "rcl/logging_rosout.h"
18 #include "rcl/node.h"
19 #include "rcl/publisher.h"
20 #include "rcl/time.h"
21 #include "rcl/types.h"
22 #include "rcl/visibility_control.h"
23 #include "rcl_interfaces/msg/log.h"
24 #include "rcutils/allocator.h"
25 #include "rcutils/logging_macros.h"
26 #include "rcutils/macros.h"
27 #include "rcutils/types/hash_map.h"
28 #include "rcutils/types/rcutils_ret.h"
29 #include "rosidl_runtime_c/string_functions.h"
30 
31 #ifdef __cplusplus
32 extern "C"
33 {
34 #endif
35 
36 #define ROSOUT_TOPIC_NAME "/rosout"
37 
38 /* Return RCL_RET_OK from this macro because we won't check throughout rcl if rosout is
39  * initialized or not and in the case it's not we want things to continue working.
40  */
41 #define RCL_LOGGING_ROSOUT_VERIFY_INITIALIZED \
42  if (!__is_initialized) { \
43  return RCL_RET_OK; \
44  }
45 
46 #define RCL_RET_FROM_RCUTIL_RET(rcl_ret_var, rcutils_expr) \
47  { \
48  rcutils_ret_t rcutils_ret = rcutils_expr; \
49  if (RCUTILS_RET_OK != rcutils_ret) { \
50  if (rcutils_error_is_set()) { \
51  RCL_SET_ERROR_MSG(rcutils_get_error_string().str); \
52  } else { \
53  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("rcutils_ret_t code: %i", rcutils_ret); \
54  } \
55  } \
56  switch (rcutils_ret) { \
57  case RCUTILS_RET_OK: \
58  rcl_ret_var = RCL_RET_OK; \
59  break; \
60  case RCUTILS_RET_ERROR: \
61  rcl_ret_var = RCL_RET_ERROR; \
62  break; \
63  case RCUTILS_RET_BAD_ALLOC: \
64  rcl_ret_var = RCL_RET_BAD_ALLOC; \
65  break; \
66  case RCUTILS_RET_INVALID_ARGUMENT: \
67  rcl_ret_var = RCL_RET_INVALID_ARGUMENT; \
68  break; \
69  case RCUTILS_RET_NOT_INITIALIZED: \
70  rcl_ret_var = RCL_RET_NOT_INIT; \
71  break; \
72  default: \
73  rcl_ret_var = RCUTILS_RET_ERROR; \
74  } \
75  }
76 
77 typedef struct rosout_map_entry_t
78 {
79  rcl_node_t * node;
80  rcl_publisher_t publisher;
82 
83 static rcutils_hash_map_t __logger_map;
84 static bool __is_initialized = false;
85 static rcl_allocator_t __rosout_allocator;
86 
88  const rcl_allocator_t * allocator)
89 {
90  RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
91  rcl_ret_t status = RCL_RET_OK;
92  if (__is_initialized) {
93  return RCL_RET_OK;
94  }
95  __logger_map = rcutils_get_zero_initialized_hash_map();
96  RCL_RET_FROM_RCUTIL_RET(
97  status,
98  rcutils_hash_map_init(
99  &__logger_map, 2, sizeof(const char *), sizeof(rosout_map_entry_t),
100  rcutils_hash_map_string_hash_func, rcutils_hash_map_string_cmp_func, allocator));
101  if (RCL_RET_OK == status) {
102  __rosout_allocator = *allocator;
103  __is_initialized = true;
104  }
105  return status;
106 }
107 
109 {
110  RCL_LOGGING_ROSOUT_VERIFY_INITIALIZED
111  rcl_ret_t status = RCL_RET_OK;
112  char * key = NULL;
113  rosout_map_entry_t entry;
114 
115  // fini all the outstanding publishers
116  rcutils_ret_t hashmap_ret = rcutils_hash_map_get_next_key_and_data(
117  &__logger_map, NULL, &key, &entry);
118  while (RCL_RET_OK == status && RCUTILS_RET_OK == hashmap_ret) {
119  // Teardown publisher
120  status = rcl_publisher_fini(&entry.publisher, entry.node);
121 
122  if (RCL_RET_OK == status) {
123  RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_unset(&__logger_map, &key));
124  }
125 
126  if (RCL_RET_OK == status) {
127  hashmap_ret = rcutils_hash_map_get_next_key_and_data(&__logger_map, NULL, &key, &entry);
128  }
129  }
130  if (RCUTILS_RET_HASH_MAP_NO_MORE_ENTRIES != hashmap_ret) {
131  RCL_RET_FROM_RCUTIL_RET(status, hashmap_ret);
132  }
133 
134  if (RCL_RET_OK == status) {
135  RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_fini(&__logger_map));
136  }
137 
138  if (RCL_RET_OK == status) {
139  __is_initialized = false;
140  }
141  return status;
142 }
143 
145  rcl_node_t * node)
146 {
147  RCL_LOGGING_ROSOUT_VERIFY_INITIALIZED
148  const char * logger_name = NULL;
149  rosout_map_entry_t new_entry;
150  rcl_ret_t status = RCL_RET_OK;
151 
152  // Verify input and make sure it's not already initialized
153  RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_NODE_INVALID);
154  logger_name = rcl_node_get_logger_name(node);
155  if (NULL == logger_name) {
156  RCL_SET_ERROR_MSG("Logger name was null.");
157  return RCL_RET_ERROR;
158  }
159  if (rcutils_hash_map_key_exists(&__logger_map, &logger_name)) {
160  // @TODO(nburek) Update behavior to either enforce unique names or work with non-unique
161  // names based on the outcome here: https://github.com/ros2/design/issues/187
162  RCUTILS_LOG_WARN_NAMED(
163  "rcl.logging_rosout",
164  "Publisher already registered for provided node name. If this is due to multiple nodes "
165  "with the same name then all logs for that logger name will go out over the existing "
166  "publisher. As soon as any node with that name is destructed it will unregister the "
167  "publisher, preventing any further logs for that name from being published on the rosout "
168  "topic.");
169  return RCL_RET_OK;
170  }
171 
172  // Create a new Log message publisher on the node
173  const rosidl_message_type_support_t * type_support =
174  rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__Log();
176 
177  // Late joining subscriptions get the user's setting of rosout qos options.
178  const rcl_node_options_t * node_options = rcl_node_get_options(node);
179  RCL_CHECK_FOR_NULL_WITH_MSG(node_options, "Node options was null.", return RCL_RET_ERROR);
180 
181  options.qos = node_options->rosout_qos;
182  options.allocator = node_options->allocator;
183  new_entry.publisher = rcl_get_zero_initialized_publisher();
184  status =
185  rcl_publisher_init(&new_entry.publisher, node, type_support, ROSOUT_TOPIC_NAME, &options);
186 
187  // Add the new publisher to the map
188  if (RCL_RET_OK == status) {
189  new_entry.node = node;
190  RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_set(&__logger_map, &logger_name, &new_entry));
191  if (RCL_RET_OK != status) {
192  RCL_SET_ERROR_MSG("Failed to add publisher to map.");
193  // We failed to add to the map so destroy the publisher that we created
194  rcl_ret_t fini_status = rcl_publisher_fini(&new_entry.publisher, new_entry.node);
195  // ignore the return status in favor of the failure from set
196  RCL_UNUSED(fini_status);
197  }
198  }
199 
200  return status;
201 }
202 
204  rcl_node_t * node)
205 {
206  RCL_LOGGING_ROSOUT_VERIFY_INITIALIZED
207  rosout_map_entry_t entry;
208  const char * logger_name = NULL;
209  rcl_ret_t status = RCL_RET_OK;
210 
211  // Verify input and make sure it's initialized
212  RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_NODE_INVALID);
213  logger_name = rcl_node_get_logger_name(node);
214  if (NULL == logger_name) {
215  return RCL_RET_ERROR;
216  }
217  if (!rcutils_hash_map_key_exists(&__logger_map, &logger_name)) {
218  return RCL_RET_OK;
219  }
220 
221  // fini the publisher and remove the entry from the map
222  RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_get(&__logger_map, &logger_name, &entry));
223  if (RCL_RET_OK == status) {
224  status = rcl_publisher_fini(&entry.publisher, entry.node);
225  }
226  if (RCL_RET_OK == status) {
227  RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_unset(&__logger_map, &logger_name));
228  }
229 
230  return status;
231 }
232 
234  const rcutils_log_location_t * location,
235  int severity,
236  const char * name,
237  rcutils_time_point_value_t timestamp,
238  const char * format,
239  va_list * args)
240 {
241  rosout_map_entry_t entry;
242  rcl_ret_t status = RCL_RET_OK;
243  if (!__is_initialized) {
244  return;
245  }
246  rcutils_ret_t rcutils_ret = rcutils_hash_map_get(&__logger_map, &name, &entry);
247  if (RCUTILS_RET_OK == rcutils_ret) {
248  char msg_buf[1024] = "";
249  rcutils_char_array_t msg_array = {
250  .buffer = msg_buf,
251  .owns_buffer = false,
252  .buffer_length = 0u,
253  .buffer_capacity = sizeof(msg_buf),
254  .allocator = __rosout_allocator
255  };
256 
257  RCL_RET_FROM_RCUTIL_RET(status, rcutils_char_array_vsprintf(&msg_array, format, *args));
258  if (RCL_RET_OK != status) {
259  RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to format log string: ");
260  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
261  rcl_reset_error();
262  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
263  } else {
264  rcl_interfaces__msg__Log * log_message = rcl_interfaces__msg__Log__create();
265  if (NULL != log_message) {
266  log_message->stamp.sec = (int32_t) RCL_NS_TO_S(timestamp);
267  log_message->stamp.nanosec = (timestamp % RCL_S_TO_NS(1));
268  log_message->level = severity;
269  log_message->line = (int32_t) location->line_number;
270  rosidl_runtime_c__String__assign(&log_message->name, name);
271  rosidl_runtime_c__String__assign(&log_message->msg, msg_array.buffer);
272  rosidl_runtime_c__String__assign(&log_message->file, location->file_name);
273  rosidl_runtime_c__String__assign(&log_message->function, location->function_name);
274  status = rcl_publish(&entry.publisher, log_message, NULL);
275  if (RCL_RET_OK != status) {
276  RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to publish log message to rosout: ");
277  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
278  rcl_reset_error();
279  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
280  }
281 
282  rcl_interfaces__msg__Log__destroy(log_message);
283  }
284  }
285 
286  RCL_RET_FROM_RCUTIL_RET(status, rcutils_char_array_fini(&msg_array));
287  if (RCL_RET_OK != status) {
288  RCUTILS_SAFE_FWRITE_TO_STDERR("failed to fini char_array: ");
289  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
290  rcl_reset_error();
291  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
292  }
293  }
294 }
295 
296 
297 #ifdef __cplusplus
298 }
299 #endif
rcutils_allocator_t rcl_allocator_t
Encapsulation of an allocator.
Definition: allocator.h:31
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_rosout_fini()
Uninitializes the rcl_logging_rosout features.
RCL_PUBLIC void rcl_logging_rosout_output_handler(const rcutils_log_location_t *location, int severity, const char *name, rcutils_time_point_value_t timestamp, const char *format, va_list *args)
The output handler outputs log messages to rosout topics.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_rosout_init_publisher_for_node(rcl_node_t *node)
Creates a rosout publisher for a node and registers it to be used by the logging system.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_rosout_fini_publisher_for_node(rcl_node_t *node)
Deregisters a rosout publisher for a node and cleans up allocated resources.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_rosout_init(const rcl_allocator_t *allocator)
Initializes the rcl_logging_rosout features.
RCL_PUBLIC RCL_WARN_UNUSED const rcl_node_options_t * rcl_node_get_options(const rcl_node_t *node)
Return the rcl node options.
Definition: node.c:462
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_logger_name(const rcl_node_t *node)
Return the logger name of the node.
Definition: node.c:512
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publisher_init(rcl_publisher_t *publisher, const rcl_node_t *node, const rosidl_message_type_support_t *type_support, const char *topic_name, const rcl_publisher_options_t *options)
Initialize a rcl publisher.
Definition: publisher.c:46
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publish(const rcl_publisher_t *publisher, const void *ros_message, rmw_publisher_allocation_t *allocation)
Publish a ROS message on a topic using a publisher.
Definition: publisher.c:236
RCL_PUBLIC RCL_WARN_UNUSED rcl_publisher_options_t rcl_publisher_get_default_options(void)
Return the default publisher options in a rcl_publisher_options_t.
Definition: publisher.c:198
RCL_PUBLIC RCL_WARN_UNUSED rcl_publisher_t rcl_get_zero_initialized_publisher(void)
Return a rcl_publisher_t struct with members set to NULL.
Definition: publisher.c:39
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publisher_fini(rcl_publisher_t *publisher, rcl_node_t *node)
Finalize a rcl_publisher_t.
Definition: publisher.c:164
Structure which encapsulates the options for creating a rcl_node_t.
Definition: node_options.h:35
rmw_qos_profile_t rosout_qos
Middleware quality of service settings for /rosout.
Definition: node_options.h:56
rcl_allocator_t allocator
If true, no parameter infrastructure will be setup.
Definition: node_options.h:44
Structure which encapsulates a ROS Node.
Definition: node.h:42
Options available for a rcl publisher.
Definition: publisher.h:44
rmw_qos_profile_t qos
Middleware quality of service settings for the publisher.
Definition: publisher.h:46
rcl_allocator_t allocator
Custom allocator for the publisher, used for incidental allocations.
Definition: publisher.h:49
Structure which encapsulates a ROS Publisher.
Definition: publisher.h:37
#define RCL_NS_TO_S
Convenience macro to convert nanoseconds to seconds.
Definition: time.h:39
#define RCL_S_TO_NS
Convenience macro to convert seconds to nanoseconds.
Definition: time.h:32
#define RCL_RET_OK
Success return code.
Definition: types.h:26
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:34
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:28
#define RCL_RET_NODE_INVALID
Invalid rcl_node_t given return code.
Definition: types.h:56
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:23