Skip to content

Commit

Permalink
Fixup
Browse files Browse the repository at this point in the history
  • Loading branch information
nburek committed Dec 7, 2018
1 parent 5998666 commit f9029bf
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 4 deletions.
4 changes: 2 additions & 2 deletions rcl/include/rcl/logging_rosout.h
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ rcl_logging_rosout_fini_publisher_for_node(
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
Expand All @@ -160,7 +160,7 @@ 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 * log_str);
const char * format, va_list * args);

#ifdef __cplusplus
}
Expand Down
27 changes: 25 additions & 2 deletions rcl/src/rcl/logging_rosout.c
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ rcl_ret_t rcl_logging_rosout_fini_publisher_for_node(
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 * log_str)
const char * format, va_list * args)
{
rosout_map_entry_t entry;
rcl_ret_t status = RCL_RET_OK;
Expand All @@ -188,20 +188,43 @@ void rcl_logging_rosout_output_handler(
}
status = rcutils_hash_map_get(&__logger_map, &name, &entry);
if (RCL_RET_OK == status) {
char msg_buf[1024] = "";
rcutils_char_array_t msg_array = {
.buffer = msg_buf,
.owns_buffer = false,
.buffer_length = 0u,
.buffer_capacity = sizeof(msg_buf),
.allocator = __rosout_allocator
};

va_list args_clone;
va_copy(args_clone, *args);
status = rcutils_char_array_vsprintf(&msg_array, format, args_clone);
va_end(args_clone);


rcl_interfaces__msg__Log * log_message = rcl_interfaces__msg__Log__create();
if (NULL != log_message) {
log_message->stamp.sec = (timestamp / 1000000000);
log_message->stamp.nanosec = (timestamp % 1000000000);
log_message->level = severity;
log_message->line = location->line_number;
rosidl_generator_c__String__assign(&log_message->name, name);
rosidl_generator_c__String__assign(&log_message->msg, log_str);
rosidl_generator_c__String__assign(&log_message->msg, msg_array.buffer);
rosidl_generator_c__String__assign(&log_message->file, location->file_name);
rosidl_generator_c__String__assign(&log_message->function, location->function_name);
status = rcl_publish(&entry.publisher, log_message);

rcl_interfaces__msg__Log__destroy(log_message);
}

status = rcutils_char_array_fini(&msg_array);
if (RCL_RET_OK != status) {
RCUTILS_SAFE_FWRITE_TO_STDERR("failed to fini char_array: ");
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
rcl_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
}
}
}

Expand Down

0 comments on commit f9029bf

Please sign in to comment.