ROS 2 rclcpp + rcl - humble
humble
ROS 2 C++ Client Library with ROS Client Library
|
#include "rcl/allocator.h"
#include "rcl/error_handling.h"
#include "rcl/node.h"
#include "rcl/types.h"
#include "rcl/visibility_control.h"
Go to the source code of this file.
Functions | |
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t | rcl_logging_rosout_init (const rcl_allocator_t *allocator) |
Initializes the rcl_logging_rosout features. More... | |
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t | rcl_logging_rosout_fini () |
Uninitializes the rcl_logging_rosout features. More... | |
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. More... | |
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. More... | |
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. More... | |
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_rosout_fini | ( | ) |
Uninitializes the rcl_logging_rosout features.
Calling this will set the rcl_logging_rosout features into the an unitialized state that is functionally the same as before rcl_logging_rosout_init was called.
Attribute | Adherence |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Yes |
Definition at line 108 of file logging_rosout.c.
References rcl_publisher_fini(), and RCL_RET_OK.
Referenced by rcl_logging_fini().
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.
Calling this for an rcl_node_t will destroy the rosout publisher on that node and remove it from the logging system so that no more Log messages are published to this function.
Attribute | Adherence |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Yes |
[in] | node | a valid rcl_node_t that the publisher will be created on |
Definition at line 203 of file logging_rosout.c.
References rcl_node_get_logger_name(), rcl_publisher_fini(), RCL_RET_ERROR, RCL_RET_NODE_INVALID, and RCL_RET_OK.
Referenced by rcl_node_fini(), and rcl_node_init().
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_rosout_init | ( | const rcl_allocator_t * | allocator | ) |
Initializes the rcl_logging_rosout features.
Calling this will initialize the rcl_logging_rosout features. This function must be called before any other rcl_logging_rosout_* functions can be called.
Attribute | Adherence |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Yes |
[in] | allocator | The allocator used for metadata related to the rcl_logging_rosout features |
Definition at line 87 of file logging_rosout.c.
References RCL_RET_INVALID_ARGUMENT, and RCL_RET_OK.
Referenced by rcl_logging_configure_with_output_handler().
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.
Calling this for an rcl_node_t will create a new publisher on that node that will be used by the logging system to publish all log messages from that Node's logger.
If a publisher already exists for this node then a new publisher will NOT be created.
It is expected that after creating a rosout publisher with this function rcl_logging_destroy_rosout_publisher_for_node() will be called for the node to cleanup the publisher while the Node is still valid.
Attribute | Adherence |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Yes |
[in] | node | a valid rcl_node_t that the publisher will be created on |
Definition at line 144 of file logging_rosout.c.
References rcl_node_options_s::allocator, rcl_publisher_options_s::allocator, rcl_publisher_options_s::qos, rcl_get_zero_initialized_publisher(), rcl_node_get_logger_name(), rcl_node_get_options(), rcl_publisher_fini(), rcl_publisher_get_default_options(), rcl_publisher_init(), RCL_RET_ERROR, RCL_RET_NODE_INVALID, RCL_RET_OK, and rcl_node_options_s::rosout_qos.
Referenced by rcl_node_init().
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.
When called with a logger name and log message this function will attempt to find a rosout publisher correlated with the logger name and publish a Log message out via that publisher. If there is no publisher directly correlated with the logger then nothing will be done.
This function is meant to be registered with the logging functions for rcutils, and shouldn't be used outside of that context. Additionally, arguments like args should be non-null and properly initialized otherwise it is undefined behavior.
Attribute | Adherence |
---|---|
Allocates Memory | Yes |
Thread-Safe | No |
Uses Atomics | No |
Lock-Free | Yes |
[in] | location | The pointer to the location struct or NULL |
[in] | severity | The severity level |
[in] | name | The name of the logger, must be null terminated c string |
[in] | timestamp | The timestamp for when the log message was made |
[in] | format | The list of arguments to insert into the formatted log message |
[in] | args | argument for the string format |
Definition at line 233 of file logging_rosout.c.
References RCL_NS_TO_S, rcl_publish(), RCL_RET_OK, and RCL_S_TO_NS.
Referenced by rcl_logging_configure_with_output_handler().