rcl
master
C API providing common ROS client library functionality.
|
#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_LOCAL rcl_ret_t | rcl_logging_rosout_init (const rcl_allocator_t *allocator) |
Initializes the rcl_logging_rosout features. More... | |
RCL_LOCAL rcl_ret_t | rcl_logging_rosout_fini () |
Uninitializes the rcl_logging_rosout features. More... | |
RCL_LOCAL 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_LOCAL 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... | |
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_LOCAL 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 |
RCL_RET_OK
if the rcl_logging_rosout features are successfully initialized, or RCL_RET_INVALID_ARGUMENT
if any arguments are invalid, or RCL_RET_BAD_ALLOC
if allocating memory failed, or RCL_RET_ERROR
if an unspecified error occurs. 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 |
RCL_RET_OK
if the rcl_logging_rosout feature was successfully unitialized, or RCL_RET_ERROR
if an unspecified error occurs. RCL_LOCAL 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 |
RCL_RET_OK
if the publisher was created successfully, or RCL_RET_ALREADY_INIT
if the publisher has already exists, or RCL_RET_NODE_INVALID
if any arguments are invalid, or RCL_RET_BAD_ALLOC
if allocating memory failed, or RCL_RET_ERROR
if an unspecified error occurs. RCL_LOCAL 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 |
RCL_RET_OK
if the publisher was created successfully, or RCL_RET_NODE_INVALID
if any arguments are invalid, or RCL_RET_BAD_ALLOC
if allocating memory failed, or RCL_RET_ERROR
if an unspecified error occurs. 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
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] | log_str | The string to be logged |