rclc icon indicating copy to clipboard operation
rclc copied to clipboard

Feature request: Logging like ros2 node.get_logger()

Open JanStaschulat opened this issue 4 years ago • 23 comments

A ROS2 node provides a handy interface for log messages. Something like node.get_logger().info(). You all know we can view these messages in rqt and other tools.

It seems that such a function is not availabe in micro-ros

BR Patrick

see previous ticket: https://github.com/micro-ROS/rclc/issues/77 see also: https://github.com/micro-ROS/rclc/issues/75 @PaddyCube We are transferring all tickets/PR to ros2/rclc repository. The micro-ros organization shall only be used for feature branches based on ros2/rclc. That's why I created this ticket on ros2/rclc and closed your ticket on micro-ros/rclc.

JanStaschulat avatar Feb 26 '21 08:02 JanStaschulat

Meanwhile I tried to publish to rosout topic by myself but I had no luck.

#include <rcl_interfaces/msg/log.h>

rcl_publisher_t publisher_log;
rcl_interfaces__msg__Log msgLog;

	// create publisher
	RCCHECK(rclc_publisher_init_default(
		&publisher_log,
		&node,
		ROSIDL_GET_MSG_TYPE_SUPPORT(rcl_interfaces, msg, Log),
		"rosout"));


		msgLog.level = rcl_interfaces__msg__Log__INFO;
		msgLog.name.data = (char *)"ESP32 ";
		msgLog.name.size = strlen(msgLog.name.data);
		msgLog.msg.data = (char *)"Hello World";
		msgLog.msg.size = strlen(msgLog.msg.data);
		RCSOFTCHECK(rcl_publish(&publisher_log, &msgLog, NULL));

Everything compiles without any warning and I'm able to flash. During execution, it fails when creating the publisher with this error message

[ERROR] [0000000002.693165000] [rclc]: [rclc_publisher_init_default] Error in rcl_publisher_init: error not set

Any ideas of what's going wrong?

PaddyCube avatar Mar 02 '21 19:03 PaddyCube

RCCHECK(rclc_publisher_init_default(...) does not print out the error message. You could add in the next line RCLC_WARN(rclc, rcl_publish) https://github.com/ros2/rclc/blob/1b8d45a0bb63704e5aab91f3eeb7530cff414318/rclc/include/rclc/types.h#L56 both arguments are arbitrary literals. This will output the error message set by the rclc_publisher_init_default() and reset it again.

Or print out the error message yourself using rcutils_get_error_string().str and reset the error message string with rcl_reset_error(); as in the macro.

Do you have a link to your application code? As I don't see the entire setup code, just two thoughts:

  • do you initialize ROS context (like in this example)?
  • do you use multiple threads? (please keep in mind XRCE-DDS supports only single threaded usage)

JanStaschulat avatar Mar 02 '21 21:03 JanStaschulat

Does it works with any other topic name that is not rosout?

pablogs9 avatar Mar 03 '21 06:03 pablogs9

Does it works with any other topic name that is not rosout?

It doesn't make any difference if I change it to something else.

PaddyCube avatar Mar 03 '21 08:03 PaddyCube

Could you share the whole demo code to replicate it?

pablogs9 avatar Mar 03 '21 08:03 pablogs9

RCCHECK(rclc_publisher_init_default(...) does not print out the error message. You could add in the next line RCLC_WARN(rclc, rcl_publish) https://github.com/ros2/rclc/blob/1b8d45a0bb63704e5aab91f3eeb7530cff414318/rclc/include/rclc/types.h#L56

both arguments are arbitrary literals. This will output the error message set by the rclc_publisher_init_default() and reset it again. Or print out the error message yourself using rcutils_get_error_string().str and reset the error message string with rcl_reset_error(); as in the macro.

Do you have a link to your application code? As I don't see the entire setup code, just two thoughts:

  • do you initialize ROS context (like in this example)?
  • do you use multiple threads? (please keep in mind XRCE-DDS supports only single threaded usage)

I tried to get a more detailled error message like you mentioned but it doesn't enlight anything to me.

	// // create publisher
	 RCCHECK(rclc_publisher_init_default(
	 	&publisher_log,
	 	&node,
	 	ROSIDL_GET_MSG_TYPE_SUPPORT(rcl_interfaces, msg, Log),
	 	"rosout"));
		 
		 ESP_LOGW(TAG, "Error: %s", rcutils_get_error_string().str);
		 rcl_reset_error();
W (2438) Ardumower: microROS agent connected
UDP mode => ip: 192.168.178.65 - port: 8888
[ERROR] [0000000009.288699000] [rclc]: [rclc_publisher_init_default] Error in rcl_publisher_init: error not set

Failed status on line 137: 1. Aborting.
W (2548) Ardumower: Error: error not set
[INFO] [0000000009.298169000] []: Created a timer with period 1000 ms.

I'm using two tasks but all ROS related things are runnig inside the same task. Currently, I use one task to monitor all incoming uart traffic and place this into a queue. ROS task observes this queue and publishes all messages as string message.

I use a timer to publish messages to rosout just for testing. Without using this publisher, the entire code works.


#include <string.h>
#include <stdio.h>
#include <unistd.h>

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "esp_log.h"
#include "esp_system.h"

extern "C"
{
#include <uros_network_interfaces.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <std_msgs/msg/int32.h>
#include <std_msgs/msg/string.h>
#include <rcl_interfaces/msg/log.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <rmw_uros/options.h>
#include "uxr/client/config.h"
}

#include "driver/gpio.h"
#include "sdkconfig.h"
#include "uart_task.h"

extern "C"
{
	void app_main(void);
}

static const char *TAG = "Ardumower";
QueueHandle_t uartQueue = NULL;
QueueHandle_t inboundMessageQueue = NULL;

// ROS Definitions
#define RCCHECK(fn)                                                                      \
	{                                                                                    \
		rcl_ret_t temp_rc = fn;                                                          \
		if ((temp_rc != RCL_RET_OK))                                                     \
		{                                                                                \
			printf("Failed status on line %d: %d. Aborting.\n", __LINE__, (int)temp_rc); \
		}                                                                                \
	}
#define RCSOFTCHECK(fn)                                                                    \
	{                                                                                      \
		rcl_ret_t temp_rc = fn;                                                            \
		if ((temp_rc != RCL_RET_OK))                                                       \
		{                                                                                  \
			printf("Failed status on line %d: %d. Continuing.\n", __LINE__, (int)temp_rc); \
		}                                                                                  \
	}

rcl_publisher_t publisher_int32;
rcl_publisher_t publisher_string;
rcl_publisher_t publisher_log;
std_msgs__msg__Int32 msgInt;
std_msgs__msg__String msgStr;
rcl_interfaces__msg__Log msgLog;

void timer_callback(rcl_timer_t *timer, int64_t last_call_time)
{
	RCLC_UNUSED(last_call_time);
	if (timer != NULL)
	{
		RCSOFTCHECK(rcl_publish(&publisher_int32, &msgInt, NULL));
		msgInt.data = msgInt.data + 5;

		 msgLog.level = rcl_interfaces__msg__Log__INFO;
		 msgLog.name.data = (char *)"ESP32 ";
		 msgLog.name.size = strlen(msgLog.name.data);
		 msgLog.msg.data = (char *)"Hello World";
		 msgLog.msg.size = strlen(msgLog.msg.data);
		 RCSOFTCHECK(rcl_publish(&publisher_log, &msgLog, NULL));
	}
}

void micro_ros_task(void *arg)
{

	rcl_allocator_t allocator = rcl_get_default_allocator();
	rclc_support_t support;

	rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
	RCCHECK(rcl_init_options_init(&init_options, allocator));
	rmw_init_options_t *rmw_options = rcl_init_options_get_rmw_init_options(&init_options);

	// Static Agent IP and port can be used instead of autodisvery.
	//RCCHECK(rmw_uros_options_set_udp_address(CONFIG_MICRO_ROS_AGENT_IP, CONFIG_MICRO_ROS_AGENT_PORT, rmw_options));
	if ((strlen(CONFIG_MICRO_ROS_AGENT_IP) != 0) && (CONFIG_MICRO_ROS_AGENT_PORT != 0) && (strcmp(CONFIG_MICRO_ROS_AGENT_IP, "-") != 0))
	{
		while (rmw_uros_options_set_udp_address(
				   CONFIG_MICRO_ROS_AGENT_IP, CONFIG_MICRO_ROS_AGENT_PORT, rmw_options) != RCL_RET_OK)
		{
			ESP_LOGW(TAG, "microROS %s %s agent not found", CONFIG_MICRO_ROS_AGENT_IP, CONFIG_MICRO_ROS_AGENT_PORT);
			usleep(1000);
		}
	}
	else
	{
		while (rmw_uros_discover_agent(rmw_options) != RCL_RET_OK)
		{
			ESP_LOGW(TAG, "microROS agent not found");
			usleep(1000);
		}
	}
	ESP_LOGW(TAG, "microROS agent connected");

	// create init_options
	RCCHECK(rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator));

	// create node
	rcl_node_t node;
	RCCHECK(rclc_node_init_default(&node, "esp32_int32_publisher", "", &support));

	// create publisher
	RCCHECK(rclc_publisher_init_default(
		&publisher_int32,
		&node,
		ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
		"freertos_int32_publisher"));

	// create publisher
	RCCHECK(rclc_publisher_init_default(
		&publisher_string,
		&node,
		ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),
		"ardumower_uart"));

	// // create publisher
	 RCCHECK(rclc_publisher_init_default(
	 	&publisher_log,
	 	&node,
	 	ROSIDL_GET_MSG_TYPE_SUPPORT(rcl_interfaces, msg, Log),
	 	"rosout"));
		 
		 ESP_LOGW(TAG, "Error: %s", rcutils_get_error_string().str);
		 rcl_reset_error();

	// create timer,
	rcl_timer_t timer;
	const unsigned int timer_timeout = 1000;
	RCCHECK(rclc_timer_init_default(
		&timer,
		&support,
		RCL_MS_TO_NS(timer_timeout),
		timer_callback));

	// create executor
	rclc_executor_t executor;
	RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
	RCCHECK(rclc_executor_add_timer(&executor, &timer));

	msgInt.data = 0;
	uint8_t *data = (uint8_t *)malloc(BUF_SIZE);
	while (1)
	{
		if (inboundMessageQueue != NULL)
		{

			if (xQueueReceive(inboundMessageQueue, data, (TickType_t)(10)) == pdPASS)
			{
				//ESP_LOGI(TAG, "data avaialble");
				ESP_LOGI(TAG, "ros2: %s", data);
				msgStr.data.data = (char *)data;
				//msgStr.data.size = BUF_SIZE;
				//msgStr.data.data = "Hello from micro-ROS ";
				msgStr.data.size = strlen(msgStr.data.data);
				RCSOFTCHECK(rcl_publish(&publisher_string, &msgStr, NULL));
			}
		}

		rclc_executor_spin_some(&executor, RCL_MS_TO_NS(1));
		//usleep(10000);
	}
	// free resources
	RCCHECK(rcl_publisher_fini(&publisher_int32, &node));
	RCCHECK(rcl_publisher_fini(&publisher_string, &node));
	RCCHECK(rcl_publisher_fini(&publisher_log, &node));
	RCCHECK(rcl_node_fini(&node));

	vTaskDelete(NULL);
}

void app_main(void)
{
#ifdef UCLIENT_PROFILE_UDP
	// Start the networking if required
	ESP_ERROR_CHECK(uros_network_interface_initialize());
#endif // UCLIENT_PROFILE_UDP

	// Create Queue to transform received UART messages
	inboundMessageQueue = xQueueCreate(20, BUF_SIZE);
	setup_uart();
	//pin micro-ros task in APP_CPU to make PRO_CPU to deal with wifi:
	xTaskCreate(micro_ros_task,
				"uros_task",
				CONFIG_MICRO_ROS_APP_STACK,
				NULL,
				CONFIG_MICRO_ROS_APP_TASK_PRIO,
				NULL);
	// UART monitor Task
	xTaskCreate(uart_task, "uart_task", UART_TASK_STACK_SIZE, NULL, 20, NULL);
}

PaddyCube avatar Mar 03 '21 08:03 PaddyCube

Are you using the micro_ros_espidf_component?

Make sure that you are building the library with enough static memory allocations: https://github.com/micro-ROS/micro_ros_espidf_component/blob/dac6f808f059e40a11d9e210ff20512a106474ac/colcon.meta#L39


If you are using micro_ros_setup check your app-colcon.meta

pablogs9 avatar Mar 03 '21 09:03 pablogs9

Thank you for your support. You can find the entire code here https://github.com/PaddyCube/ArdumowerROS/tree/Development/Code/esp32

You're right, I'm using esp-idf components. I wasn't aware that there is a limitation of publishers set to 1. It was working with two publishers anyway. Why was this possible?

What is the overall limit of publishers and subscribers? My robot sends lot of information about different sensors at different intervalls (50ms and up to 5 sec). Also it raises events like bumper hit, cliff sensors and others, which I need to publish to ROS2.

I wanted to use different messages and publishers for this. Does it mean it is not feasable with micro-ros?

PaddyCube avatar Mar 03 '21 09:03 PaddyCube

Are you using the micro_ros_espidf_component?

Make sure that you are building the library with enough static memory allocations: https://github.com/micro-ROS/micro_ros_espidf_component/blob/dac6f808f059e40a11d9e210ff20512a106474ac/colcon.meta#L39

If you are using micro_ros_setup check your app-colcon.meta

I tried to increase the max_publishers to 10 but it doesn't make any difference

PaddyCube avatar Mar 03 '21 09:03 PaddyCube

Please detail which build system are you using and detail the process of rebuilding because in some cases you need to clean some files to have a complete rebuild.

pablogs9 avatar Mar 03 '21 10:03 pablogs9

We are getting closer

I'm using idf.py at ESP-IDF v4.3-dev-2586-g526f68239 and did a idf.py clean and idf.py build again.

Now I'm able to create a publisher, yeah. But now it fails as soon as I try to publish a message. I'm doing it this way:

void timer_callback(rcl_timer_t *timer, int64_t last_call_time)
{
	RCLC_UNUSED(last_call_time);
	if (timer != NULL)
	{
		RCSOFTCHECK(rcl_publish(&publisher_int32, &msgInt, NULL));
		msgInt.data = msgInt.data + 5;

			char *messageLog = "Hello world";
			char *messageName = "ESP32";
		 msgLog.level = rcl_interfaces__msg__Log__INFO;
		 msgLog.name.data = messageName;
		 msgLog.name.size = strlen(msgLog.name.data);
		 msgLog.msg.data = messageLog;
		 msgLog.msg.size = strlen(msgLog.msg.data);
		 RCSOFTCHECK(rcl_publish(&publisher_log, &msgLog, NULL));
	}
}

and get this errors which causes ESP32 to reboot


Guru Meditation Error: Core  0 panic'ed (LoadProhibited). Exception was unhandled.

Core  0 register dump:
PC      : 0x400014fd  PS      : 0x00060030  A0      : 0x800dd90c  A1      : 0x3ffd23f0  
A2      : 0x00000000  A3      : 0xfffffffc  A4      : 0x000000ff  A5      : 0x0000ff00  
A6      : 0x00ff0000  A7      : 0xff000000  A8      : 0x00000000  A9      : 0x3ffd23b0  
A10     : 0x00000001  A11     : 0x00000001  A12     : 0x00000001  A13     : 0x00000028  
A14     : 0x0000000c  A15     : 0x00000000  SAR     : 0x00000000  EXCCAUSE: 0x0000001c  
EXCVADDR: 0x00000000  LBEG    : 0x400014fd  LEND    : 0x4000150d  LCOUNT  : 0xffffffff  

Backtrace:0x400014fa:0x3ffd23f0 0x400dd909:0x3ffd2400 0x400d98b6:0x3ffd2420 0x400dc530:0x3ffd2440 0x400d96ed:0x3ffd2490 0x400d8836:0x3ffd24b0 0x400e1965:0x3ffd24d0 0x400d9cb5:0x3ffd2510 0x400da790:0x3ffd2d30 0x400d8a29:0x3ffd5600 0x4008b951:0x3ffd5710
0x400dd909: ucdr_serialize_string at ??:?

0x400d98b6: _Log__cdr_serialize at log__type_support_c.c:?

0x400dc530: rmw_publish at ??:?

0x400d96ed: rcl_publish at ??:?

0x400d8836: timer_callback(rcl_timer_t*, long long) at /home/ros/esp32/ArdumowerMircoRos/build/../main/app_main.cpp:79 (discriminator 3)

0x400e1965: rcl_timer_call at ??:?

0x400d9cb5: _rclc_execute at executor.c:?

0x400da790: rclc_executor_spin_some at ??:?

0x400d8a29: micro_ros_task(void*) at /home/ros/esp32/ArdumowerMircoRos/build/../main/app_main.cpp:178

0x4008b951: vPortTaskWrapper at /home/ros/esp32/esp-idf/components/freertos/port/xtensa/port.c:168

PaddyCube avatar Mar 03 '21 10:03 PaddyCube

Ok, I have not replicated the issue but I have seen that the rcl_interfaces__msg__Log has these members:

typedef struct rcl_interfaces__msg__Log
{
  builtin_interfaces__msg__Time stamp;
  uint8_t level;
  rosidl_runtime_c__String name;
  rosidl_runtime_c__String msg;
  rosidl_runtime_c__String file;
  rosidl_runtime_c__String function;
  uint32_t line;
} rcl_interfaces__msg__Log;

In micro-ROS by now you need to init all the members (at least string and sequences) in order to serialize correctly. So try to init also file and function at least as empty strings.

Let me know if this solves the issue.

pablogs9 avatar Mar 03 '21 13:03 pablogs9

Hello pablogs9,

thank you for all your support. This did the trick. For anyone who asks this, here all neccessary steps:

Include Log message #include <rcl_interfaces/msg/log.h>

Create publisher

rcl_publisher_t publisher_log;

	  RCCHECK(rclc_publisher_init_default(
	  	&publisher_log,
	  	&node,
	  	ROSIDL_GET_MSG_TYPE_SUPPORT(rcl_interfaces, msg, Log),
	  	"rosout"));

Publish message

                rcl_interfaces__msg__Log msgLog;
		  msgLog.level = rcl_interfaces__msg__Log__INFO;
		  msgLog.name.data = "ESP32";
		  msgLog.name.size = strlen(msgLog.name.data);
		  msgLog.msg.data = "Hello world";
		  msgLog.msg.size = strlen(msgLog.msg.data);
		  msgLog.file.data = "";
		  msgLog.file.size = strlen(msgLog.file.data);
		  msgLog.function.data = "";
		  msgLog.function.size = strlen(msgLog.function.data);
		  msgLog.line = NULL;
		  RCSOFTCHECK(rcl_publish(&publisher_log, &msgLog, NULL));

Output of ros2 topic echo /rosout

stamp:
  sec: 0
  nanosec: 0
level: 20
name: ESP32
msg: Hello world
file: ''
function: ''
line: 0
---

As are limited in count of Publishers, it might doesn't make sense to include this functionality as part of rclc by default.

PaddyCube avatar Mar 04 '21 06:03 PaddyCube

I think that we should think about integrating this along the rclc/rcl in order to get a logging interface like ROS 2.

Which user API will you expect to have @PaddyCube? Which kind of tracing info should the inner layers send?

pablogs9 avatar Mar 04 '21 06:03 pablogs9

Hello, I think I'm not able to answer this question. I'm not familiar with micro-ros neither rcl. In best case, we get some macro or function like a ros2 node provides by using mynode.get_logger().Info() or similar.

I also don't understand what you mean with tracing info of inner layer. In my opinion, it should send these information:

  • type of log info (info, debug, warn, error, fatal)
  • source (name of node)
  • message itself

PaddyCube avatar Mar 15 '21 13:03 PaddyCube

Now that some time has passed: @pablogs9: would https://github.com/ros2/rclc/issues/55#issuecomment-790354834 still be the best/most straightforward way for a micro-ROS application to log to rosout?

Or would it be possible to rely on rcutils_logging_*(..) and rcutils_log(..) to do the right thing (and automagically log to rosout as well)?

gavanderhoorn avatar Aug 10 '22 18:08 gavanderhoorn

Now that some time has passed: @pablogs9: would https://github.com/ros2/rclc/issues/55#issuecomment-790354834 still be the best/most straightforward way for a micro-ROS application to log to rosout?

That's it

pablogs9 avatar Aug 11 '22 06:08 pablogs9

None of the functionality in rcutils can be used?


Edit: what about implementing a package which provides an implementation of rcl_logging and setting RCL_LOGGING_IMPLEMENTATION?

gavanderhoorn avatar Aug 11 '22 06:08 gavanderhoorn

None of the functionality in rcutils can be used?

I should recheck this, but if I remember well, most of the logging functionality is removed in micro-ROS's rcutils due to the abuse of dynamic memory in string handling. Check here: https://github.com/micro-ROS/rcutils/commits/humble

Edit: what about implementing a package which provides an implementation of rcl_logging and setting RCL_LOGGING_IMPLEMENTATION?

This should be possible.

pablogs9 avatar Aug 11 '22 06:08 pablogs9

I should recheck this, but if I remember well, most of the logging functionality is removed in micro-ROS's rcutils due to the abuse of dynamic memory in string handling. Check here: https://github.com/micro-ROS/rcutils/commits/humble

IIUC, you're mostly referring to these changes to error_handling.h, correct?

gavanderhoorn avatar Aug 11 '22 09:08 gavanderhoorn

IIUC, you're mostly referring to these changes to error_handling.h, correct?

yes

pablogs9 avatar Aug 11 '22 09:08 pablogs9

Ok, so rcutils is out -- not too important for me.

I'm struggling a bit trying to understand how rcl/logging.h and rcl/logging_rosout.h are/could be involved.

With RCL_LOGGING_ENABLED=ON, getting rosout enabled seems to go through rcl_logging_rosout_init(..), via rcl_logging_configure_with_output_handler(..), via rcl_logging_configure(..).

Should I be able to call rcl_logging_configure(..) after getting hold of a suitably initialised rcl_arguments_t instance (which I have I believe https://github.com/micro-ROS/micro_ros_setup/discussions/557)?

There don't appear to be any #ifdefs in micro-ROS/rcl, other than RCL_LOGGING_ENABLED which block this.


Edit: rcl_node_init(..) seems to call rcl_logging_rosout_init_publisher_for_node(..) if rosout logging is enabled and rcl_node_options_t::enable_rosout is true -- which it is by default (rcl_node_get_default_options()).

@pablogs9: I'm obviously missing something, as it doesn't look like the rosout sink is being created.


Edit 2: calling rcl_logging_configure(..) does indeed create the sink.

It doesn't appear to be publishing anything though.


Edit 3: afaict, rcutils first uses RCUTILS_SAFE_FWRITE_TO_STDERR(..) (which is a no-op due to RCUTILS_NO_FILESYSTEM:ON), then subsequently calls the g_rcutils_logging_output_handler (which should have been set by rcl_logging_configure(..)).


Eidt 4: I've verified rcutils_log(..) gets called. Somehow only the console sink gets the message. I'm not sure why yet.

gavanderhoorn avatar Aug 11 '22 09:08 gavanderhoorn

Ok, for platforms where RCL_LOGGING_ENABLED=ON is acceptable, the following will enable logging to rosout (so things like rqt_console receive your log msgs):

rcl_node_options_t node_options = rcl_node_get_default_options();
// it's not absolutely necessary to call rcl_parse_arguments(..) here, as
// logging to 'rosout' is enabled by default in 'rcl_node_options_t'
rcl_logging_configure_with_output_handler(..., rcl_logging_multiple_output_handler);
rclc_node_init_with_options(..., &node_options);

at this point, calls to RCUTILS_LOG_INFO_NAMED(...) et al. will result in msgs on /rosout (in addition to stdout logging, if that exists).

I believe this is essentially the (minimum) sequence of functions client libraries also call to enable logging. I've probably missed some documentation which explains this.

Note: probably because I've not initialised something, calls to RCUTILS_LOG_*(...) (so not the NAMED variants) won't work, as the name argument passed is NULL. rcl_logging_rosout_output_handler does not like that and will drop your log msg.

And you might need to set RCUTILS_LOG_MIN_SEVERITY=RCUTILS_LOG_MIN_SEVERITY_X when building (with X one of the log levels), otherwise the logging macros get no-opped.

gavanderhoorn avatar Aug 12 '22 11:08 gavanderhoorn