ROS 2 rclcpp + rcl - kilted  kilted
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/logging_rosout.h"
16 
17 #include "rcl/allocator.h"
18 #include "rcl/common.h"
19 #include "rcl/error_handling.h"
20 #include "rcl/node.h"
21 #include "rcl/publisher.h"
22 #include "rcl/time.h"
23 #include "rcl/types.h"
24 #include "rcl/visibility_control.h"
25 #include "rcl_interfaces/msg/log.h"
26 #include "rcutils/allocator.h"
27 #include "rcutils/format_string.h"
28 #include "rcutils/logging_macros.h"
29 #include "rcutils/macros.h"
30 #include "rcutils/types/hash_map.h"
31 #include "rcutils/types/rcutils_ret.h"
32 #include "rosidl_runtime_c/string_functions.h"
33 
34 #define ROSOUT_TOPIC_NAME "/rosout"
35 
36 typedef struct rosout_map_entry_t
37 {
38  rcl_node_t * node;
39  rcl_publisher_t publisher;
41 
42 static rcutils_hash_map_t __logger_map;
43 static bool __is_initialized = false;
44 static rcl_allocator_t __rosout_allocator;
45 
47 {
48  // name is to store the allocated memory, and then finalize it at the end
49  char * name;
50  // count is something like a reference count that removes the entry if it is 0
51  uint64_t * count;
53 
54 static rcutils_hash_map_t __sublogger_map;
55 
57 {
58  RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
59  rcl_ret_t status = RCL_RET_OK;
60  if (__is_initialized) {
61  return RCL_RET_OK;
62  }
63  __logger_map = rcutils_get_zero_initialized_hash_map();
64  status = rcl_convert_rcutils_ret_to_rcl_ret(
65  rcutils_hash_map_init(
66  &__logger_map, 2, sizeof(const char *), sizeof(rosout_map_entry_t),
67  rcutils_hash_map_string_hash_func, rcutils_hash_map_string_cmp_func, allocator));
68  if (RCL_RET_OK != status) {
69  return status;
70  }
71 
72  __sublogger_map = rcutils_get_zero_initialized_hash_map();
73  status = rcl_convert_rcutils_ret_to_rcl_ret(
74  rcutils_hash_map_init(
75  &__sublogger_map, 2, sizeof(const char *), sizeof(rosout_sublogger_entry_t),
76  rcutils_hash_map_string_hash_func, rcutils_hash_map_string_cmp_func, allocator));
77  if (RCL_RET_OK != status) {
78  rcl_ret_t fini_status = rcl_convert_rcutils_ret_to_rcl_ret(
79  rcutils_hash_map_fini(&__logger_map));
80  if (RCL_RET_OK != fini_status) {
81  RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to finalize the hash map for logger: ");
82  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
83  rcl_reset_error();
84  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
85  }
86  return status;
87  }
88 
89  __rosout_allocator = *allocator;
90  __is_initialized = true;
91 
92  return status;
93 }
94 
95 static rcl_ret_t
96 _rcl_logging_rosout_remove_logger_map(rcl_node_t * node)
97 {
98  RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
99 
100  rcl_ret_t status = RCL_RET_OK;
101  char * previous_key = NULL;
102  char * key = NULL;
103  rosout_map_entry_t entry;
104  rcutils_ret_t hashmap_ret = rcutils_hash_map_get_next_key_and_data(
105  &__logger_map, NULL, &key, &entry);
106  while (RCL_RET_OK == status && RCUTILS_RET_OK == hashmap_ret) {
107  if (entry.node == node) {
108  status = rcl_convert_rcutils_ret_to_rcl_ret(rcutils_hash_map_unset(&__logger_map, &key));
109  previous_key = NULL;
110  } else {
111  previous_key = key;
112  }
113  if (RCL_RET_OK == status) {
114  hashmap_ret = rcutils_hash_map_get_next_key_and_data(
115  &__logger_map, previous_key ? &previous_key : NULL, &key, &entry);
116  }
117  }
118  return RCL_RET_OK;
119 }
120 
121 static rcl_ret_t
122 _rcl_logging_rosout_clear_logger_map_item(void * value)
123 {
124  rosout_map_entry_t * entry = (rosout_map_entry_t *)value;
125  // Teardown publisher
126  rcl_ret_t status = rcl_publisher_fini(&entry->publisher, entry->node);
127  if (RCL_RET_OK == status) {
128  // delete all entries using this node
129  status = rcl_convert_rcutils_ret_to_rcl_ret(
130  _rcl_logging_rosout_remove_logger_map(entry->node));
131  }
132 
133  return status;
134 }
135 
136 static rcl_ret_t
137 _rcl_logging_rosout_clear_sublogger_map_item(void * value)
138 {
140  rcl_ret_t status = rcl_convert_rcutils_ret_to_rcl_ret(
141  rcutils_hash_map_unset(&__sublogger_map, &entry->name));
142  __rosout_allocator.deallocate(entry->name, __rosout_allocator.state);
143  __rosout_allocator.deallocate(entry->count, __rosout_allocator.state);
144 
145  return status;
146 }
147 
148 static rcl_ret_t
149 _rcl_logging_rosout_clear_hashmap(
150  rcutils_hash_map_t * map, rcl_ret_t (* predicate)(void *), void * entry)
151 {
152  rcl_ret_t status = RCL_RET_OK;
153  char * key = NULL;
154 
155  rcutils_ret_t hashmap_ret = rcutils_hash_map_get_next_key_and_data(
156  map, NULL, &key, entry);
157  while (RCUTILS_RET_OK == hashmap_ret) {
158  status = predicate(entry);
159  if (RCL_RET_OK != status) {
160  break;
161  }
162 
163  hashmap_ret = rcutils_hash_map_get_next_key_and_data(map, NULL, &key, entry);
164  }
165  if (RCUTILS_RET_HASH_MAP_NO_MORE_ENTRIES != hashmap_ret) {
166  status = rcl_convert_rcutils_ret_to_rcl_ret(hashmap_ret);
167  }
168 
169  if (RCL_RET_OK == status) {
170  status = rcl_convert_rcutils_ret_to_rcl_ret(rcutils_hash_map_fini(map));
171  }
172 
173  return status;
174 }
175 
177 {
178  if (!__is_initialized) {
179  return RCL_RET_OK;
180  }
181  rcl_ret_t status = RCL_RET_OK;
182  rosout_map_entry_t entry;
183  rosout_sublogger_entry_t sublogger_entry;
184 
185  status = _rcl_logging_rosout_clear_hashmap(
186  &__logger_map, _rcl_logging_rosout_clear_logger_map_item, &entry);
187  if (RCL_RET_OK != status) {
188  return status;
189  }
190 
191  status = _rcl_logging_rosout_clear_hashmap(
192  &__sublogger_map, _rcl_logging_rosout_clear_sublogger_map_item, &sublogger_entry);
193  if (RCL_RET_OK != status) {
194  return status;
195  }
196 
197  __is_initialized = false;
198 
199  return status;
200 }
201 
203 {
204  if (!__is_initialized) {
205  return RCL_RET_OK;
206  }
207 
208  const char * logger_name = NULL;
209  rosout_map_entry_t new_entry;
210  rcl_ret_t status = RCL_RET_OK;
211 
212  // Verify input and make sure it's not already initialized
213  RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_NODE_INVALID);
214  logger_name = rcl_node_get_logger_name(node);
215  if (NULL == logger_name) {
216  // rcl_node_get_logger_name already set the error
217  return RCL_RET_ERROR;
218  }
219  if (rcutils_hash_map_key_exists(&__logger_map, &logger_name)) {
220  // @TODO(nburek) Update behavior to either enforce unique names or work with non-unique
221  // names based on the outcome here: https://github.com/ros2/design/issues/187
222  const char * node_name = rcl_node_get_name(node);
223  if (NULL == node_name) {
224  node_name = "unknown node";
225  }
226 
227  RCUTILS_LOG_WARN_NAMED(
228  "rcl.logging_rosout",
229  "Publisher already registered for node name: '%s'. If this is due to multiple nodes "
230  "with the same name then all logs for the logger named '%s' will go out over "
231  "the existing publisher. As soon as any node with that name is destructed "
232  "it will unregister the publisher, preventing any further logs for that name from "
233  "being published on the rosout topic.",
234  node_name,
235  logger_name);
236  return RCL_RET_OK;
237  }
238 
239  // Create a new Log message publisher on the node
240  const rosidl_message_type_support_t * type_support =
241  rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__Log();
243 
244  // Late joining subscriptions get the user's setting of rosout qos options.
245  const rcl_node_options_t * node_options = rcl_node_get_options(node);
246  RCL_CHECK_FOR_NULL_WITH_MSG(node_options, "Node options was null.", return RCL_RET_ERROR);
247 
248  options.qos = node_options->rosout_qos;
249  options.allocator = node_options->allocator;
250  new_entry.publisher = rcl_get_zero_initialized_publisher();
251  status =
252  rcl_publisher_init(&new_entry.publisher, node, type_support, ROSOUT_TOPIC_NAME, &options);
253 
254  // Add the new publisher to the map
255  if (RCL_RET_OK == status) {
256  new_entry.node = node;
257  status = rcl_convert_rcutils_ret_to_rcl_ret(
258  rcutils_hash_map_set(&__logger_map, &logger_name, &new_entry));
259  if (RCL_RET_OK != status) {
260  RCL_SET_ERROR_MSG("Failed to add publisher to map.");
261  // We failed to add to the map so destroy the publisher that we created
262  rcl_ret_t fini_status = rcl_publisher_fini(&new_entry.publisher, new_entry.node);
263  // ignore the return status in favor of the failure from set
264  RCL_UNUSED(fini_status);
265  }
266  }
267 
268  return status;
269 }
270 
272 {
273  if (!__is_initialized) {
274  return RCL_RET_OK;
275  }
276 
277  rosout_map_entry_t entry;
278  const char * logger_name = NULL;
279  rcl_ret_t status = RCL_RET_OK;
280 
281  // Verify input and make sure it's initialized
282  RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_NODE_INVALID);
283  logger_name = rcl_node_get_logger_name(node);
284  if (NULL == logger_name) {
285  return RCL_RET_ERROR;
286  }
287  if (!rcutils_hash_map_key_exists(&__logger_map, &logger_name)) {
288  return RCL_RET_OK;
289  }
290 
291  // fini the publisher and remove the entry from the map
292  status = rcl_convert_rcutils_ret_to_rcl_ret(
293  rcutils_hash_map_get(&__logger_map, &logger_name, &entry));
294  if (RCL_RET_OK == status && node == entry.node) {
295  status = rcl_publisher_fini(&entry.publisher, entry.node);
296  }
297  if (RCL_RET_OK == status) {
298  // delete all entries using this node
299  status = rcl_convert_rcutils_ret_to_rcl_ret(_rcl_logging_rosout_remove_logger_map(entry.node));
300  }
301 
302  return status;
303 }
304 
305 static void shallow_assign(rosidl_runtime_c__String * target, const char * source)
306 {
307  target->data = (char *)source;
308  size_t len = strlen(source);
309  target->size = len;
310  target->capacity = len + 1;
311 }
312 
314  const rcutils_log_location_t * location,
315  int severity,
316  const char * name,
317  rcutils_time_point_value_t timestamp,
318  const char * format,
319  va_list * args)
320 {
321  rosout_map_entry_t entry;
322  rcl_ret_t status = RCL_RET_OK;
323  if (!__is_initialized) {
324  return;
325  }
326  rcutils_ret_t rcutils_ret = rcutils_hash_map_get(&__logger_map, &name, &entry);
327  if (RCUTILS_RET_OK == rcutils_ret) {
328  char msg_buf[1024] = "";
329  rcutils_char_array_t msg_array = {
330  .buffer = msg_buf,
331  .owns_buffer = false,
332  .buffer_length = 0u,
333  .buffer_capacity = sizeof(msg_buf),
334  .allocator = __rosout_allocator
335  };
336 
337  status = rcl_convert_rcutils_ret_to_rcl_ret(
338  rcutils_char_array_vsprintf(&msg_array, format, *args));
339  if (RCL_RET_OK != status) {
340  RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to format log string: ");
341  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
342  rcl_reset_error();
343  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
344  } else {
345  rcl_interfaces__msg__Log log_message;
346  log_message.stamp.sec = (int32_t) RCL_NS_TO_S(timestamp);
347  log_message.stamp.nanosec = (timestamp % RCL_S_TO_NS(1));
348  log_message.level = severity;
349  log_message.line = (int32_t) location->line_number;
350  shallow_assign(&log_message.name, name);
351  shallow_assign(&log_message.msg, msg_array.buffer);
352  shallow_assign(&log_message.file, location->file_name);
353  shallow_assign(&log_message.function, location->function_name);
354  status = rcl_publish(&entry.publisher, &log_message, NULL);
355  if (RCL_RET_OK != status) {
356  RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to publish log message to rosout: ");
357  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
358  rcl_reset_error();
359  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
360  }
361  }
362 
363  status = rcl_convert_rcutils_ret_to_rcl_ret(rcutils_char_array_fini(&msg_array));
364  if (RCL_RET_OK != status) {
365  RCUTILS_SAFE_FWRITE_TO_STDERR("failed to fini char_array: ");
366  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
367  rcl_reset_error();
368  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
369  }
370  }
371 }
372 
373 static rcl_ret_t
374 _rcl_logging_rosout_get_full_sublogger_name(
375  const char * logger_name, const char * sublogger_name, char ** full_sublogger_name)
376 {
377  RCL_CHECK_ARGUMENT_FOR_NULL(logger_name, RCL_RET_INVALID_ARGUMENT);
378  RCL_CHECK_ARGUMENT_FOR_NULL(sublogger_name, RCL_RET_INVALID_ARGUMENT);
379  RCL_CHECK_ARGUMENT_FOR_NULL(full_sublogger_name, RCL_RET_INVALID_ARGUMENT);
380 
381  if (logger_name[0] == '\0' || sublogger_name[0] == '\0') {
382  RCL_SET_ERROR_MSG("logger name or sub-logger name can't be empty.");
384  }
385 
386  *full_sublogger_name = rcutils_format_string(
387  __rosout_allocator, "%s%s%s",
388  logger_name, RCUTILS_LOGGING_SEPARATOR_STRING, sublogger_name);
389  if (NULL == *full_sublogger_name) {
390  RCL_SET_ERROR_MSG("Failed to allocate a full sublogger name.");
391  return RCL_RET_BAD_ALLOC;
392  }
393 
394  return RCL_RET_OK;
395 }
396 
397 rcl_ret_t
399  const char * logger_name, const char * sublogger_name)
400 {
401  if (!__is_initialized) {
402  return RCL_RET_OK;
403  }
404 
405  rcl_ret_t status = RCL_RET_OK;
406  char * full_sublogger_name = NULL;
407  uint64_t * sublogger_count = NULL;
408  rosout_map_entry_t entry;
409  rosout_sublogger_entry_t sublogger_entry;
410 
411  RCL_CHECK_ARGUMENT_FOR_NULL(logger_name, RCL_RET_INVALID_ARGUMENT);
412  RCL_CHECK_ARGUMENT_FOR_NULL(sublogger_name, RCL_RET_INVALID_ARGUMENT);
413  rcutils_ret_t rcutils_ret = rcutils_hash_map_get(&__logger_map, &logger_name, &entry);
414  if (RCUTILS_RET_OK != rcutils_ret) {
415  if (RCUTILS_RET_NOT_FOUND == rcutils_ret) {
416  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("Failed to get logger entry for '%s'.", logger_name);
417  }
418  return rcl_convert_rcutils_ret_to_rcl_ret(rcutils_ret);
419  }
420 
421  status =
422  _rcl_logging_rosout_get_full_sublogger_name(logger_name, sublogger_name, &full_sublogger_name);
423  if (RCL_RET_OK != status) {
424  // Error already set
425  return status;
426  }
427 
428  if (rcutils_hash_map_key_exists(&__logger_map, &full_sublogger_name)) {
429  // To get the entry and increase the reference count
430  status = rcl_convert_rcutils_ret_to_rcl_ret(
431  rcutils_hash_map_get(&__sublogger_map, &full_sublogger_name, &sublogger_entry));
432  if (RCL_RET_OK != status) {
433  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
434  "Failed to get item from sublogger map for '%s'.", full_sublogger_name);
435  goto cleanup;
436  }
437  *sublogger_entry.count += 1;
438  goto cleanup;
439  }
440 
441  status = rcl_convert_rcutils_ret_to_rcl_ret(
442  rcutils_hash_map_set(&__logger_map, &full_sublogger_name, &entry));
443  if (RCL_RET_OK != status) {
444  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
445  "Failed to add publisher to map for logger '%s'.", full_sublogger_name);
446  goto cleanup;
447  }
448 
449  sublogger_entry.name = full_sublogger_name;
450  sublogger_count = __rosout_allocator.allocate(sizeof(uint64_t), __rosout_allocator.state);
451  if (!sublogger_count) {
452  RCL_SET_ERROR_MSG(
453  "Failed to allocate memory for count of sublogger entry.");
454  goto cleanup;
455  }
456  sublogger_entry.count = sublogger_count;
457  *sublogger_entry.count = 1;
458 
459  status = rcl_convert_rcutils_ret_to_rcl_ret(
460  rcutils_hash_map_set(&__sublogger_map, &full_sublogger_name, &sublogger_entry));
461  if (RCL_RET_OK != status) {
462  // revert the previor set operation for __logger_map
463  rcutils_ret_t rcutils_ret = rcutils_hash_map_unset(&__logger_map, &full_sublogger_name);
464  if (RCUTILS_RET_OK != rcutils_ret) {
465  RCUTILS_SAFE_FWRITE_TO_STDERR("failed to unset hashmap: ");
466  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
467  rcl_reset_error();
468  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
469  }
470  goto cleanup_count;
471  }
472 
473  return status;
474 
475 cleanup_count:
476  __rosout_allocator.deallocate(sublogger_count, __rosout_allocator.state);
477 cleanup:
478  __rosout_allocator.deallocate(full_sublogger_name, __rosout_allocator.state);
479  return status;
480 }
481 
482 rcl_ret_t
484  const char * logger_name, const char * sublogger_name)
485 {
486  if (!__is_initialized) {
487  return RCL_RET_OK;
488  }
489 
490  rcl_ret_t status = RCL_RET_OK;
491  char * full_sublogger_name = NULL;
492  rosout_sublogger_entry_t sublogger_entry;
493  RCL_CHECK_ARGUMENT_FOR_NULL(logger_name, RCL_RET_INVALID_ARGUMENT);
494  RCL_CHECK_ARGUMENT_FOR_NULL(sublogger_name, RCL_RET_INVALID_ARGUMENT);
495 
496  status =
497  _rcl_logging_rosout_get_full_sublogger_name(logger_name, sublogger_name, &full_sublogger_name);
498  if (RCL_RET_OK != status) {
499  // Error already set
500  return status;
501  }
502 
503  if (!rcutils_hash_map_key_exists(&__logger_map, &full_sublogger_name)) {
504  status = RCL_RET_NOT_FOUND;
505  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("Logger for '%s' not found.", full_sublogger_name);
506  goto cleanup;
507  }
508 
509  // remove the entry from the map
510  status = rcl_convert_rcutils_ret_to_rcl_ret(
511  rcutils_hash_map_get(&__sublogger_map, &full_sublogger_name, &sublogger_entry));
512  if (RCL_RET_OK != status) {
513  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
514  "Failed to get item from sublogger map for '%s'.", full_sublogger_name);
515  goto cleanup;
516  }
517 
518  *sublogger_entry.count -= 1;
519  if (*sublogger_entry.count == 0) {
520  status = rcl_convert_rcutils_ret_to_rcl_ret(
521  rcutils_hash_map_unset(&__logger_map, &full_sublogger_name));
522  if (RCL_RET_OK == status) {
523  status = rcl_convert_rcutils_ret_to_rcl_ret(
524  rcutils_hash_map_unset(&__sublogger_map, &full_sublogger_name));
525  __rosout_allocator.deallocate(sublogger_entry.name, __rosout_allocator.state);
526  __rosout_allocator.deallocate(sublogger_entry.count, __rosout_allocator.state);
527  }
528  }
529 
530 cleanup:
531  __rosout_allocator.deallocate(full_sublogger_name, __rosout_allocator.state);
532  return status;
533 }
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_add_sublogger(const char *logger_name, const char *sublogger_name)
Add a subordinate logger based on a logger.
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_fini(void)
Uninitializes the rcl_logging_rosout features.
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 rcl_ret_t rcl_logging_rosout_remove_sublogger(const char *logger_name, const char *sublogger_name)
Remove a subordinate logger and cleans up allocated resources.
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:435
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_name(const rcl_node_t *node)
Return the name of the node.
Definition: node.c:408
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:485
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:48
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:271
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:220
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:40
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:179
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:45
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_NOT_FOUND
Resource not found.
Definition: types.h:55
#define RCL_RET_OK
Success return code.
Definition: types.h:27
#define RCL_RET_BAD_ALLOC
Failed to allocate memory return code.
Definition: types.h:33
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:35
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:29
#define RCL_RET_NODE_INVALID
Invalid rcl_node_t given return code.
Definition: types.h:59
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24