16 #include "rcl/error_handling.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"
36 #define ROSOUT_TOPIC_NAME "/rosout"
41 #define RCL_LOGGING_ROSOUT_VERIFY_INITIALIZED \
42 if (!__is_initialized) { \
46 #define RCL_RET_FROM_RCUTIL_RET(rcl_ret_var, rcutils_expr) \
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); \
53 RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("rcutils_ret_t code: %i", rcutils_ret); \
56 switch (rcutils_ret) { \
57 case RCUTILS_RET_OK: \
58 rcl_ret_var = RCL_RET_OK; \
60 case RCUTILS_RET_ERROR: \
61 rcl_ret_var = RCL_RET_ERROR; \
63 case RCUTILS_RET_BAD_ALLOC: \
64 rcl_ret_var = RCL_RET_BAD_ALLOC; \
66 case RCUTILS_RET_INVALID_ARGUMENT: \
67 rcl_ret_var = RCL_RET_INVALID_ARGUMENT; \
69 case RCUTILS_RET_NOT_INITIALIZED: \
70 rcl_ret_var = RCL_RET_NOT_INIT; \
73 rcl_ret_var = RCUTILS_RET_ERROR; \
83 static rcutils_hash_map_t __logger_map;
84 static bool __is_initialized =
false;
92 if (__is_initialized) {
95 __logger_map = rcutils_get_zero_initialized_hash_map();
96 RCL_RET_FROM_RCUTIL_RET(
98 rcutils_hash_map_init(
100 rcutils_hash_map_string_hash_func, rcutils_hash_map_string_cmp_func, allocator));
102 __rosout_allocator = *allocator;
103 __is_initialized =
true;
110 RCL_LOGGING_ROSOUT_VERIFY_INITIALIZED
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) {
123 RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_unset(&__logger_map, &key));
127 hashmap_ret = rcutils_hash_map_get_next_key_and_data(&__logger_map, NULL, &key, &entry);
130 if (RCUTILS_RET_HASH_MAP_NO_MORE_ENTRIES != hashmap_ret) {
131 RCL_RET_FROM_RCUTIL_RET(status, hashmap_ret);
135 RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_fini(&__logger_map));
139 __is_initialized =
false;
147 RCL_LOGGING_ROSOUT_VERIFY_INITIALIZED
148 const char * logger_name = NULL;
155 if (NULL == logger_name) {
156 RCL_SET_ERROR_MSG(
"Logger name was null.");
159 if (rcutils_hash_map_key_exists(&__logger_map, &logger_name)) {
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 "
173 const rosidl_message_type_support_t * type_support =
174 rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__Log();
179 RCL_CHECK_FOR_NULL_WITH_MSG(node_options,
"Node options was null.",
return RCL_RET_ERROR);
185 rcl_publisher_init(&new_entry.publisher, node, type_support, ROSOUT_TOPIC_NAME, &options);
189 new_entry.node = node;
190 RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_set(&__logger_map, &logger_name, &new_entry));
192 RCL_SET_ERROR_MSG(
"Failed to add publisher to map.");
196 RCL_UNUSED(fini_status);
206 RCL_LOGGING_ROSOUT_VERIFY_INITIALIZED
208 const char * logger_name = NULL;
214 if (NULL == logger_name) {
217 if (!rcutils_hash_map_key_exists(&__logger_map, &logger_name)) {
222 RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_get(&__logger_map, &logger_name, &entry));
227 RCL_RET_FROM_RCUTIL_RET(status, rcutils_hash_map_unset(&__logger_map, &logger_name));
234 const rcutils_log_location_t * location,
237 rcutils_time_point_value_t timestamp,
243 if (!__is_initialized) {
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 = {
251 .owns_buffer =
false,
253 .buffer_capacity =
sizeof(msg_buf),
254 .allocator = __rosout_allocator
257 RCL_RET_FROM_RCUTIL_RET(status, rcutils_char_array_vsprintf(&msg_array, format, *args));
259 RCUTILS_SAFE_FWRITE_TO_STDERR(
"Failed to format log string: ");
260 RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
262 RCUTILS_SAFE_FWRITE_TO_STDERR(
"\n");
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);
276 RCUTILS_SAFE_FWRITE_TO_STDERR(
"Failed to publish log message to rosout: ");
277 RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
279 RCUTILS_SAFE_FWRITE_TO_STDERR(
"\n");
282 rcl_interfaces__msg__Log__destroy(log_message);
286 RCL_RET_FROM_RCUTIL_RET(status, rcutils_char_array_fini(&msg_array));
288 RCUTILS_SAFE_FWRITE_TO_STDERR(
"failed to fini char_array: ");
289 RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
291 RCUTILS_SAFE_FWRITE_TO_STDERR(
"\n");
rcutils_allocator_t rcl_allocator_t
Encapsulation of an allocator.
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.
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_logger_name(const rcl_node_t *node)
Return the logger name of the node.
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.
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.
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.
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.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publisher_fini(rcl_publisher_t *publisher, rcl_node_t *node)
Finalize a rcl_publisher_t.
Structure which encapsulates the options for creating a rcl_node_t.
rmw_qos_profile_t rosout_qos
Middleware quality of service settings for /rosout.
rcl_allocator_t allocator
If true, no parameter infrastructure will be setup.
Structure which encapsulates a ROS Node.
Options available for a rcl publisher.
rmw_qos_profile_t qos
Middleware quality of service settings for the publisher.
rcl_allocator_t allocator
Custom allocator for the publisher, used for incidental allocations.
Structure which encapsulates a ROS Publisher.
#define RCL_NS_TO_S
Convenience macro to convert nanoseconds to seconds.
#define RCL_S_TO_NS
Convenience macro to convert seconds to nanoseconds.
#define RCL_RET_OK
Success return code.
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
#define RCL_RET_ERROR
Unspecified error return code.
#define RCL_RET_NODE_INVALID
Invalid rcl_node_t given return code.
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.