From ffdc9d629cfa78223a23d193bc244b0cd2486e20 Mon Sep 17 00:00:00 2001
From: Mark Charlebois <charlebm@gmail.com>
Date: Tue, 19 May 2015 09:19:24 -0700
Subject: [PATCH] POSIX: Improved logging

The warnx and warn calls map to PX4_WARN.
Calls to errx or err genrtate a compile error.

The px4_log.h file implements a new log format:

For DEBUG and INFO:
<level> <msg>

For ERROR and WARN:
<level> <msg> (file filepath line linenum)

The verbosity can be changed by setting the macro to use
either linux_log or linux_log_verbose in px4_log.h

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
---
 src/drivers/device/device_posix.cpp           |  2 +-
 src/drivers/device/sim.cpp                    |  8 +-
 src/drivers/device/vdev.cpp                   | 57 +++++++------
 src/drivers/device/vdev_posix.cpp             | 20 ++---
 src/drivers/led/led.cpp                       |  2 +-
 src/modules/simulator/simulator.cpp           | 14 ++--
 src/modules/simulator/simulator_mavlink.cpp   |  4 +-
 src/modules/systemlib/err.h                   | 10 +++
 src/modules/systemlib/module.mk               |  5 +-
 .../posix/drivers/accelsim/accelsim.cpp       |  2 +-
 src/platforms/posix/drivers/barosim/baro.cpp  | 81 +++++++++----------
 .../posix/drivers/barosim/baro_sim.cpp        |  6 +-
 .../posix/drivers/gyrosim/gyrosim.cpp         |  4 +-
 .../posix/drivers/tonealrmsim/tone_alarm.cpp  |  2 +-
 .../posix/px4_layer/px4_posix_tasks.cpp       | 23 +++++-
 src/platforms/px4_log.h                       | 31 ++++---
 .../qurt/px4_layer/px4_qurt_tasks.cpp         |  2 +-
 17 files changed, 157 insertions(+), 116 deletions(-)

diff --git a/src/drivers/device/device_posix.cpp b/src/drivers/device/device_posix.cpp
index 34382263ac..771bee2471 100644
--- a/src/drivers/device/device_posix.cpp
+++ b/src/drivers/device/device_posix.cpp
@@ -83,7 +83,7 @@ Device::log(const char *fmt, ...)
 {
 	va_list	ap;
 
-	printf("[%s] ", _name);
+	PX4_INFO("[%s] ", _name);
 	va_start(ap, fmt);
 	vprintf(fmt, ap);
 	va_end(ap);
diff --git a/src/drivers/device/sim.cpp b/src/drivers/device/sim.cpp
index 4e952409eb..787a3826c9 100644
--- a/src/drivers/device/sim.cpp
+++ b/src/drivers/device/sim.cpp
@@ -63,7 +63,7 @@ SIM::SIM(const char *name,
 	_devname(devname)
 {
 
-	PX4_DBG("SIM::SIM name = %s devname = %s", name, devname);
+	PX4_DEBUG("SIM::SIM name = %s devname = %s", name, devname);
 	// fill in _device_id fields for a SIM device
 	_device_id.devid_s.bus_type = DeviceBusType_SIM;
 	_device_id.devid_s.bus = bus;
@@ -99,16 +99,16 @@ int
 SIM::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len)
 {
 	if (send_len > 0) {
-		PX4_DBG("SIM: sending %d bytes", send_len);
+		PX4_DEBUG("SIM: sending %d bytes", send_len);
 	}
 
 	if (recv_len > 0) {
-		PX4_DBG("SIM: receiving %d bytes", recv_len);
+		PX4_DEBUG("SIM: receiving %d bytes", recv_len);
 		
 		// TODO - write data to recv;
 	}
 
-	PX4_DBG("I2C SIM: transfer_4 on %s", _devname);
+	PX4_DEBUG("I2C SIM: transfer_4 on %s", _devname);
 
 	return PX4_OK;
 }
diff --git a/src/drivers/device/vdev.cpp b/src/drivers/device/vdev.cpp
index 9efdb63e8a..50fe6ed697 100644
--- a/src/drivers/device/vdev.cpp
+++ b/src/drivers/device/vdev.cpp
@@ -84,12 +84,14 @@ VDev::VDev(const char *name,
 	_registered(false),
 	_open_count(0)
 {
+	PX4_DEBUG("VDev::VDev");
 	for (unsigned i = 0; i < _max_pollwaiters; i++)
 		_pollset[i] = nullptr;
 }
 
 VDev::~VDev()
 {
+	PX4_DEBUG("VDev::~VDev");
 	if (_registered)
 		unregister_driver(_devname);
 }
@@ -97,6 +99,7 @@ VDev::~VDev()
 int
 VDev::register_class_devname(const char *class_devname)
 {
+	PX4_DEBUG("VDev::register_class_devname");
 	if (class_devname == nullptr) {
 		return -EINVAL;
 	}
@@ -121,6 +124,7 @@ VDev::register_class_devname(const char *class_devname)
 int
 VDev::register_driver(const char *name, void *data)
 {
+	PX4_DEBUG("VDev::register_driver");
 	int ret = -ENOSPC;
 
 	if (name == NULL || data == NULL)
@@ -136,7 +140,7 @@ VDev::register_driver(const char *name, void *data)
 	for (int i=0;i<PX4_MAX_DEV; ++i) {
 		if (devmap[i] == NULL) {
 			devmap[i] = new px4_dev_t(name, (void *)data);
-			debug("Registered DEV %s", name);
+			PX4_DEBUG("Registered DEV %s", name);
 			ret = PX4_OK;
 			break;
 		}
@@ -147,6 +151,7 @@ VDev::register_driver(const char *name, void *data)
 int
 VDev::unregister_driver(const char *name)
 {
+	PX4_DEBUG("VDev::unregister_driver");
 	int ret = -ENOSPC;
 
 	if (name == NULL)
@@ -156,7 +161,7 @@ VDev::unregister_driver(const char *name)
 		if (devmap[i] && (strcmp(name, devmap[i]->name) == 0)) {
 			delete devmap[i];
 			devmap[i] = NULL;
-			debug("Unregistered DEV %s", name);
+			PX4_DEBUG("Unregistered DEV %s", name);
 			ret = PX4_OK;
 			break;
 		}
@@ -167,12 +172,13 @@ VDev::unregister_driver(const char *name)
 int
 VDev::unregister_class_devname(const char *class_devname, unsigned class_instance)
 {
+	PX4_DEBUG("VDev::unregister_class_devname");
 	char name[32];
 	snprintf(name, sizeof(name), "%s%u", class_devname, class_instance);
 	for (int i=0;i<PX4_MAX_DEV; ++i) {
 		if (devmap[i] && strcmp(devmap[i]->name,name) == 0) {
 			delete devmap[i];
-			debug("Unregistered class DEV %s", name);
+			PX4_DEBUG("Unregistered class DEV %s", name);
 			devmap[i] = NULL;
 			return PX4_OK;
 		}
@@ -183,6 +189,8 @@ VDev::unregister_class_devname(const char *class_devname, unsigned class_instanc
 int
 VDev::init()
 {
+	PX4_DEBUG("VDev::init");
+
 	// base class init first
 	int ret = Device::init();
 
@@ -209,9 +217,9 @@ out:
 int
 VDev::open(file_t *filep)
 {
+	PX4_DEBUG("VDev::open");
 	int ret = PX4_OK;
 
-	debug("VDev::open");
 	lock();
 	/* increment the open count */
 	_open_count++;
@@ -233,14 +241,14 @@ VDev::open(file_t *filep)
 int
 VDev::open_first(file_t *filep)
 {
-	debug("VDev::open_first");
+	PX4_DEBUG("VDev::open_first");
 	return PX4_OK;
 }
 
 int
 VDev::close(file_t *filep)
 {
-	debug("VDev::close");
+	PX4_DEBUG("VDev::close");
 	int ret = PX4_OK;
 
 	lock();
@@ -265,36 +273,37 @@ VDev::close(file_t *filep)
 int
 VDev::close_last(file_t *filep)
 {
-	debug("VDev::close_last");
+	PX4_DEBUG("VDev::close_last");
 	return PX4_OK;
 }
 
 ssize_t
 VDev::read(file_t *filep, char *buffer, size_t buflen)
 {
-	debug("VDev::read");
+	PX4_DEBUG("VDev::read");
 	return -ENOSYS;
 }
 
 ssize_t
 VDev::write(file_t *filep, const char *buffer, size_t buflen)
 {
-	debug("VDev::write");
+	PX4_DEBUG("VDev::write");
 	return -ENOSYS;
 }
 
 off_t
 VDev::seek(file_t *filep, off_t offset, int whence)
 {
+	PX4_DEBUG("VDev::seek");
 	return -ENOSYS;
 }
 
 int
 VDev::ioctl(file_t *filep, int cmd, unsigned long arg)
 {
+	PX4_DEBUG("VDev::ioctl");
 	int ret = -ENOTTY;
 
-	debug("VDev::ioctl");
 	switch (cmd) {
 
 		/* fetch a pointer to the driver's private data */
@@ -311,7 +320,7 @@ VDev::ioctl(file_t *filep, int cmd, unsigned long arg)
 		break;
         case DEVIOCGDEVICEID:
                 ret = (int)_device_id.devid;
-		printf("IOCTL DEVIOCGDEVICEID %d\n", ret);
+		PX4_INFO("IOCTL DEVIOCGDEVICEID %d", ret);
 	default:
 		break;
 	}
@@ -322,8 +331,8 @@ VDev::ioctl(file_t *filep, int cmd, unsigned long arg)
 int
 VDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
 {
+	PX4_DEBUG("VDev::Poll %s", setup ? "setup" : "teardown");
 	int ret = PX4_OK;
-	debug("VDev::Poll %s", setup ? "setup" : "teardown");
 
 	/*
 	 * Lock against pollnotify() (and possibly other callers)
@@ -336,7 +345,7 @@ VDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
 		 * benefit.
 		 */
 		fds->priv = (void *)filep;
-		debug("VDev::poll: fds->priv = %p", filep);
+		PX4_DEBUG("VDev::poll: fds->priv = %p", filep);
 
 		/*
 		 * Handle setup requests.
@@ -371,7 +380,7 @@ VDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
 void
 VDev::poll_notify(pollevent_t events)
 {
-	debug("VDev::poll_notify events = %0x", events);
+	PX4_DEBUG("VDev::poll_notify events = %0x", events);
 
 	/* lock against poll() as well as other wakeups */
 	lock();
@@ -386,14 +395,14 @@ VDev::poll_notify(pollevent_t events)
 void
 VDev::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
 {
-	debug("VDev::poll_notify_one");
+	PX4_DEBUG("VDev::poll_notify_one");
 	int value;
 	sem_getvalue(fds->sem, &value);
 
 	/* update the reported event set */
 	fds->revents |= fds->events & events;
 
-	debug(" Events fds=%p %0x %0x %0x %d",fds, fds->revents, fds->events, events, value);
+	PX4_DEBUG(" Events fds=%p %0x %0x %0x %d",fds, fds->revents, fds->events, events, value);
 
 	/* if the state is now interesting, wake the waiter if it's still asleep */
 	/* XXX semcount check here is a vile hack; counting semphores should not be abused as cvars */
@@ -404,7 +413,7 @@ VDev::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
 pollevent_t
 VDev::poll_state(file_t *filep)
 {
-	debug("VDev::poll_notify");
+	PX4_DEBUG("VDev::poll_notify");
 	/* by default, no poll events to report */
 	return 0;
 }
@@ -415,7 +424,7 @@ VDev::store_poll_waiter(px4_pollfd_struct_t *fds)
 	/*
 	 * Look for a free slot.
 	 */
-	debug("VDev::store_poll_waiter");
+	PX4_DEBUG("VDev::store_poll_waiter");
 	for (unsigned i = 0; i < _max_pollwaiters; i++) {
 		if (nullptr == _pollset[i]) {
 
@@ -432,7 +441,7 @@ VDev::store_poll_waiter(px4_pollfd_struct_t *fds)
 int
 VDev::remove_poll_waiter(px4_pollfd_struct_t *fds)
 {
-	debug("VDev::remove_poll_waiter");
+	PX4_DEBUG("VDev::remove_poll_waiter");
 	for (unsigned i = 0; i < _max_pollwaiters; i++) {
 		if (fds == _pollset[i]) {
 
@@ -442,13 +451,13 @@ VDev::remove_poll_waiter(px4_pollfd_struct_t *fds)
 		}
 	}
 
-	puts("poll: bad fd state");
+	PX4_WARN("poll: bad fd state");
 	return -EINVAL;
 }
 
 VDev *VDev::getDev(const char *path)
 {
-	printf("VDev::getDev\n");
+	PX4_DEBUG("VDev::getDev");
 	int i=0;
 	for (; i<PX4_MAX_DEV; ++i) {
 		//if (devmap[i]) {
@@ -464,7 +473,7 @@ VDev *VDev::getDev(const char *path)
 void VDev::showDevices()
 {
 	int i=0;
-	printf("Devices:\n");
+	PX4_INFO("Devices:\n");
 	for (; i<PX4_MAX_DEV; ++i) {
 		if (devmap[i] && strncmp(devmap[i]->name, "/dev/", 5) == 0) {
 			printf("   %s\n", devmap[i]->name);
@@ -475,7 +484,7 @@ void VDev::showDevices()
 void VDev::showTopics()
 {
 	int i=0;
-	printf("Devices:\n");
+	PX4_INFO("Devices:\n");
 	for (; i<PX4_MAX_DEV; ++i) {
 		if (devmap[i] && strncmp(devmap[i]->name, "/obj/", 5) == 0) {
 			printf("   %s\n", devmap[i]->name);
@@ -486,7 +495,7 @@ void VDev::showTopics()
 void VDev::showFiles()
 {
 	int i=0;
-	printf("Files:\n");
+	PX4_INFO("Files:\n");
 	for (; i<PX4_MAX_DEV; ++i) {
 		if (devmap[i] && strncmp(devmap[i]->name, "/obj/", 5) != 0 &&
 				 strncmp(devmap[i]->name, "/dev/", 5) != 0) {
diff --git a/src/drivers/device/vdev_posix.cpp b/src/drivers/device/vdev_posix.cpp
index fdd2e73210..0e94e88dfe 100644
--- a/src/drivers/device/vdev_posix.cpp
+++ b/src/drivers/device/vdev_posix.cpp
@@ -71,7 +71,7 @@ static void *timer_handler(void *data)
 	usleep(td->ts.tv_nsec/1000);
 	sem_post(&(td->sem));
 
-	PX4_DEBUG("timer_handler: Timer expired\n");
+	PX4_DEBUG("timer_handler: Timer expired");
 	return 0;
 }
 
@@ -87,7 +87,7 @@ inline bool valid_fd(int fd)
 
 int px4_open(const char *path, int flags, ...)
 {
-	printf("px4_open\n");
+	PX4_DEBUG("px4_open");
 	VDev *dev = VDev::getDev(path);
 	int ret = 0;
 	int i;
@@ -103,7 +103,7 @@ int px4_open(const char *path, int flags, ...)
 		va_end(p);
 
 		// Create the file
-		warnx("Creating virtual file %s\n", path);
+		PX4_DEBUG("Creating virtual file %s", path);
 		dev = VFile::createFile(path, mode);
 	}
 	if (dev) {
@@ -136,7 +136,7 @@ int px4_close(int fd)
 	int ret;
 	if (valid_fd(fd)) {
 		VDev *dev = (VDev *)(filemap[fd]->vdev);
-		PX4_DEBUG("px4_close fd = %d\n", fd);
+		PX4_DEBUG("px4_close fd = %d", fd);
 		ret = dev->close(filemap[fd]);
 		filemap[fd] = NULL;
 	}
@@ -155,7 +155,7 @@ ssize_t px4_read(int fd, void *buffer, size_t buflen)
 	int ret;
 	if (valid_fd(fd)) {
 		VDev *dev = (VDev *)(filemap[fd]->vdev);
-		PX4_DEBUG("px4_read fd = %d\n", fd);
+		PX4_DEBUG("px4_read fd = %d", fd);
 		ret = dev->read(filemap[fd], (char *)buffer, buflen);
 	}
 	else { 
@@ -173,7 +173,7 @@ ssize_t px4_write(int fd, const void *buffer, size_t buflen)
 	int ret;
         if (valid_fd(fd)) {
 		VDev *dev = (VDev *)(filemap[fd]->vdev);
-		PX4_DEBUG("px4_write fd = %d\n", fd);
+		PX4_DEBUG("px4_write fd = %d", fd);
 		ret = dev->write(filemap[fd], (const char *)buffer, buflen);
 	}
 	else { 
@@ -188,7 +188,7 @@ ssize_t px4_write(int fd, const void *buffer, size_t buflen)
 
 int px4_ioctl(int fd, int cmd, unsigned long arg)
 {
-	PX4_DEBUG("px4_ioctl fd = %d\n", fd);
+	PX4_DEBUG("px4_ioctl fd = %d", fd);
 	int ret = 0;
         if (valid_fd(fd)) {
 		VDev *dev = (VDev *)(filemap[fd]->vdev);
@@ -212,7 +212,7 @@ int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout)
 	unsigned int i;
 	struct timespec ts;
 
-	PX4_DEBUG("Called px4_poll timeout = %d\n", timeout);
+	PX4_DEBUG("Called px4_poll timeout = %d", timeout);
 	sem_init(&sem, 0, 0);
 
 	// For each fd 
@@ -226,7 +226,7 @@ int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout)
 		if (valid_fd(fds[i].fd))
 		{
 			VDev *dev = (VDev *)(filemap[fds[i].fd]->vdev);;
-			PX4_DEBUG("px4_poll: VDev->poll(setup) %d\n", fds[i].fd);
+			PX4_DEBUG("px4_poll: VDev->poll(setup) %d", fds[i].fd);
 			ret = dev->poll(filemap[fds[i].fd], &fds[i], true);
 
 			if (ret < 0)
@@ -270,7 +270,7 @@ int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout)
 			if (valid_fd(fds[i].fd))
 			{
 				VDev *dev = (VDev *)(filemap[fds[i].fd]->vdev);;
-				PX4_DEBUG("px4_poll: VDev->poll(teardown) %d\n", fds[i].fd);
+				PX4_DEBUG("px4_poll: VDev->poll(teardown) %d", fds[i].fd);
 				ret = dev->poll(filemap[fds[i].fd], &fds[i], false);
 	
 				if (ret < 0)
diff --git a/src/drivers/led/led.cpp b/src/drivers/led/led.cpp
index 428a542f15..69c72b5b53 100644
--- a/src/drivers/led/led.cpp
+++ b/src/drivers/led/led.cpp
@@ -89,7 +89,7 @@ LED::~LED()
 int
 LED::init()
 {
-	printf("Initializing LED\n");
+	debug("LED::init");
 #ifdef __PX4_NUTTX
 	CDev::init();
 #else
diff --git a/src/modules/simulator/simulator.cpp b/src/modules/simulator/simulator.cpp
index 1920724fdf..83e3fd8d76 100644
--- a/src/modules/simulator/simulator.cpp
+++ b/src/modules/simulator/simulator.cpp
@@ -81,7 +81,7 @@ int Simulator::start(int argc, char *argv[])
 	int ret = 0;
 	_instance = new Simulator();
 	if (_instance) {
-		PX4_INFO("Simulator started\n");
+		PX4_INFO("Simulator started");
 		drv_led_start();
 		if (argv[2][1] == 's') {
 #ifndef __PX4_QURT
@@ -92,7 +92,7 @@ int Simulator::start(int argc, char *argv[])
 		}
 	}
 	else {
-		PX4_WARN("Simulator creation failed\n");
+		PX4_WARN("Simulator creation failed");
 		ret = 1;
 	}
 	return ret;
@@ -150,7 +150,7 @@ void Simulator::publishSensorsCombined() {
 			gyro.timestamp = time_last;
 			mag.timestamp = time_last;
 			// publish the sensor values
-			//printf("Publishing SensorsCombined\n");
+			//PX4_DEBUG("Publishing SensorsCombined\n");
 			orb_publish(ORB_ID(sensor_combined), _sensor_combined_pub, &sensors);
 			orb_publish(ORB_ID(sensor_baro), _baro_pub, &baro);
 			orb_publish(ORB_ID(sensor_accel), _accel_pub, &baro);
@@ -225,14 +225,14 @@ bool static _led_state[2] = { false , false };
 
 __EXPORT void led_init()
 {
-	PX4_DBG("LED_INIT\n");
+	PX4_DEBUG("LED_INIT");
 }
 
 __EXPORT void led_on(int led)
 {
 	if (led == 1 || led == 0)
 	{
-		PX4_DBG("LED%d_ON", led);
+		PX4_DEBUG("LED%d_ON", led);
 		_led_state[led] = true;
 	}
 }
@@ -241,7 +241,7 @@ __EXPORT void led_off(int led)
 {
 	if (led == 1 || led == 0)
 	{
-		PX4_DBG("LED%d_OFF", led);
+		PX4_DEBUG("LED%d_OFF", led);
 		_led_state[led] = false;
 	}
 }
@@ -251,7 +251,7 @@ __EXPORT void led_toggle(int led)
 	if (led == 1 || led == 0)
 	{
 		_led_state[led] = !_led_state[led];
-		PX4_DBG("LED%d_TOGGLE: %s\n", led, _led_state[led] ? "ON" : "OFF");
+		PX4_DEBUG("LED%d_TOGGLE: %s", led, _led_state[led] ? "ON" : "OFF");
 
 	}
 }
diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp
index 9b6efb5102..ed4a6343fe 100644
--- a/src/modules/simulator/simulator_mavlink.cpp
+++ b/src/modules/simulator/simulator_mavlink.cpp
@@ -335,7 +335,7 @@ void Simulator::updateSamples()
 	int serial_fd = open(PIXHAWK_DEVICE, O_RDWR);
 
 	if (serial_fd < 0) {
-		PX4_WARN("failed to open %s\n", PIXHAWK_DEVICE);
+		PX4_WARN("failed to open %s", PIXHAWK_DEVICE);
 	}
 
 	// tell the device to stream some messages
@@ -343,7 +343,7 @@ void Simulator::updateSamples()
 	int w = ::write(serial_fd, command, sizeof(command));
 
 	if (w <= 0) {
-		PX4_WARN("failed to send streaming command to %s\n", PIXHAWK_DEVICE);
+		PX4_WARN("failed to send streaming command to %s", PIXHAWK_DEVICE);
 	}
 
 	char serial_buf[1024];
diff --git a/src/modules/systemlib/err.h b/src/modules/systemlib/err.h
index af90c25600..05401128ef 100644
--- a/src/modules/systemlib/err.h
+++ b/src/modules/systemlib/err.h
@@ -65,6 +65,7 @@
 #ifndef _SYSTEMLIB_ERR_H
 #define _SYSTEMLIB_ERR_H
 
+#include <px4_log.h>
 #include <stdarg.h>
 #include "visibility.h"
 
@@ -72,6 +73,14 @@ __BEGIN_DECLS
 
 __EXPORT const char *getprogname(void);
 
+#ifdef __PX4_POSIX
+
+#define err(...)					ERROR
+#define errx(...)					ERROR
+#define warn(...) 					PX4_WARN(__VA_ARGS__)
+#define warnx(...) 					PX4_WARN(__VA_ARGS__)
+
+#else
 __EXPORT void	err(int eval, const char *fmt, ...)		__attribute__((noreturn, format(printf, 2, 3)));
 __EXPORT void	verr(int eval, const char *fmt, va_list)	__attribute__((noreturn, format(printf, 2, 0)));
 __EXPORT void	errc(int eval, int code, const char *fmt, ...)	__attribute__((noreturn, format(printf, 3, 4)));
@@ -84,6 +93,7 @@ __EXPORT void	warnc(int code, const char *fmt, ...)		__attribute__((format(print
 __EXPORT void	vwarnc(int code, const char *fmt, va_list)	__attribute__((format(printf, 2, 0)));
 __EXPORT void	warnx(const char *fmt, ...)			__attribute__((format(printf, 1, 2)));
 __EXPORT void	vwarnx(const char *fmt, va_list)		__attribute__((format(printf, 1, 0)));
+#endif
 
 __END_DECLS
 
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index 0e023cf1b1..cb599e2052 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -35,7 +35,7 @@
 # System utility library
 #
 
-SRCS		 = err.c \
+SRCS		 = \
 		   perf_counter.c \
 		   param/param.c \
 		   conversions.c \
@@ -55,7 +55,8 @@ SRCS		 = err.c \
 		   circuit_breaker_params.c 
 
 ifeq ($(PX4_TARGET_OS),nuttx)
-SRCS		+= up_cxxinitialize.c 
+SRCS		+= err.c \
+		   up_cxxinitialize.c 
 endif
 
 ifneq ($(PX4_TARGET_OS),qurt)
diff --git a/src/platforms/posix/drivers/accelsim/accelsim.cpp b/src/platforms/posix/drivers/accelsim/accelsim.cpp
index 42e9eb0b1c..f431231706 100644
--- a/src/platforms/posix/drivers/accelsim/accelsim.cpp
+++ b/src/platforms/posix/drivers/accelsim/accelsim.cpp
@@ -1331,7 +1331,7 @@ info()
 		return 1;
 	}
 
-	PX4_DBG("state @ %p", g_dev);
+	PX4_DEBUG("state @ %p", g_dev);
 	//g_dev->print_info();
 
 	return 0;
diff --git a/src/platforms/posix/drivers/barosim/baro.cpp b/src/platforms/posix/drivers/barosim/baro.cpp
index 4a247f85bd..13021444c0 100644
--- a/src/platforms/posix/drivers/barosim/baro.cpp
+++ b/src/platforms/posix/drivers/barosim/baro.cpp
@@ -250,7 +250,7 @@ int
 BAROSIM::init()
 {
 	int ret;
-	PX4_WARN("BAROSIM::init");
+	debug("BAROSIM::init");
 
 	ret = VDev::init();
 	if (ret != OK) {
@@ -401,59 +401,58 @@ BAROSIM::ioctl(device::file_t *filp, int cmd, unsigned long arg)
 {
 	switch (cmd) {
 
-	case SENSORIOCSPOLLRATE: {
-			switch (arg) {
+	case SENSORIOCSPOLLRATE: 
+		switch (arg) {
 
-				/* switching to manual polling */
-			case SENSOR_POLLRATE_MANUAL:
-				stop_cycle();
-				_measure_ticks = 0;
-				return OK;
+			/* switching to manual polling */
+		case SENSOR_POLLRATE_MANUAL:
+			stop_cycle();
+			_measure_ticks = 0;
+			return OK;
 
-				/* external signalling not supported */
-			case SENSOR_POLLRATE_EXTERNAL:
+			/* external signalling not supported */
+		case SENSOR_POLLRATE_EXTERNAL:
 
-				/* zero would be bad */
-			case 0:
-				return -EINVAL;
+			/* zero would be bad */
+		case 0:
+			return -EINVAL;
 
-				/* set default/max polling rate */
-			case SENSOR_POLLRATE_MAX:
-			case SENSOR_POLLRATE_DEFAULT: {
-					/* do we need to start internal polling? */
-					bool want_start = (_measure_ticks == 0);
+			/* set default/max polling rate */
+		case SENSOR_POLLRATE_MAX:
+		case SENSOR_POLLRATE_DEFAULT: {
+				/* do we need to start internal polling? */
+				bool want_start = (_measure_ticks == 0);
 
-					/* set interval for next measurement to minimum legal value */
-					_measure_ticks = USEC2TICK(BAROSIM_CONVERSION_INTERVAL);
+				/* set interval for next measurement to minimum legal value */
+				_measure_ticks = USEC2TICK(BAROSIM_CONVERSION_INTERVAL);
 
-					/* if we need to start the poll state machine, do it */
-					if (want_start)
-						start_cycle();
+				/* if we need to start the poll state machine, do it */
+				if (want_start)
+					start_cycle();
 
-					return OK;
-				}
+				return OK;
+			}
 
-				/* adjust to a legal polling interval in Hz */
-			default: {
-					/* do we need to start internal polling? */
-					bool want_start = (_measure_ticks == 0);
+			/* adjust to a legal polling interval in Hz */
+		default: {
+				/* do we need to start internal polling? */
+				bool want_start = (_measure_ticks == 0);
 
-					/* convert hz to tick interval via microseconds */
-					unsigned ticks = USEC2TICK(1000000 / arg);
+				/* convert hz to tick interval via microseconds */
+				unsigned ticks = USEC2TICK(1000000 / arg);
 
-					/* check against maximum rate */
-					if ((long)ticks < USEC2TICK(BAROSIM_CONVERSION_INTERVAL))
-						return -EINVAL;
+				/* check against maximum rate */
+				if ((long)ticks < USEC2TICK(BAROSIM_CONVERSION_INTERVAL))
+					return -EINVAL;
 
-					/* update interval for next measurement */
-					_measure_ticks = ticks;
+				/* update interval for next measurement */
+				_measure_ticks = ticks;
 
-					/* if we need to start the poll state machine, do it */
-					if (want_start)
-						start_cycle();
+				/* if we need to start the poll state machine, do it */
+				if (want_start)
+					start_cycle();
 
-					return OK;
-				}
+				return OK;
 			}
 		}
 
diff --git a/src/platforms/posix/drivers/barosim/baro_sim.cpp b/src/platforms/posix/drivers/barosim/baro_sim.cpp
index 7c267f6aaa..734c2bc286 100644
--- a/src/platforms/posix/drivers/barosim/baro_sim.cpp
+++ b/src/platforms/posix/drivers/barosim/baro_sim.cpp
@@ -205,16 +205,16 @@ BARO_SIM::transfer(const uint8_t *send, unsigned send_len,
 		PX4_DEBUG("BARO_SIM measurement requested");
 	}
 	else if (send_len != 1 || send[0] != 0 || recv_len != 3) {
-		PX4_WARN("BARO_SIM::transfer invalid param %u %u %u\n", send_len, send[0], recv_len);
+		PX4_WARN("BARO_SIM::transfer invalid param %u %u %u", send_len, send[0], recv_len);
 		return 1;
 	}
 	else {
 		Simulator *sim = Simulator::getInstance();
 		if (sim == NULL) {
-			PX4_ERR("Error BARO_SIM::transfer no simulator \n");
+			PX4_ERR("Error BARO_SIM::transfer no simulator");
 			return -ENODEV;
 		}
-		PX4_DEBUG("BARO_SIM::transfer getting sample\n");
+		PX4_DEBUG("BARO_SIM::transfer getting sample");
 		sim->getBaroSample(recv, recv_len);
 	}
 	return 0;
diff --git a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp
index e0d50ce25d..b253ab3b0d 100644
--- a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp
+++ b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp
@@ -669,11 +669,11 @@ GYROSIM::transfer(uint8_t *send, uint8_t *recv, unsigned len)
 	}
 	else if (cmd & DIR_READ)
 	{
-		PX4_DBG("Reading %u bytes from register %u", len-1, reg);
+		PX4_DEBUG("Reading %u bytes from register %u", len-1, reg);
 		memcpy(&_regdata[reg-MPUREG_PRODUCT_ID], &send[1], len-1);
 	}
 	else {
-		PX4_DBG("Writing %u bytes to register %u", len-1, reg);
+		PX4_DEBUG("Writing %u bytes to register %u", len-1, reg);
 		if (recv)
 			memcpy(&recv[1], &_regdata[reg-MPUREG_PRODUCT_ID], len-1);
 	}
diff --git a/src/platforms/posix/drivers/tonealrmsim/tone_alarm.cpp b/src/platforms/posix/drivers/tonealrmsim/tone_alarm.cpp
index 232da9cb2d..37f51ff607 100644
--- a/src/platforms/posix/drivers/tonealrmsim/tone_alarm.cpp
+++ b/src/platforms/posix/drivers/tonealrmsim/tone_alarm.cpp
@@ -350,7 +350,7 @@ ToneAlarm::start_note(unsigned note)
 
 	// Silence warning of unused var
 	do_something(period);
-	PX4_DBG("ToneAlarm::start_note %u", period);
+	PX4_DEBUG("ToneAlarm::start_note %u", period);
 }
 
 void
diff --git a/src/platforms/posix/px4_layer/px4_posix_tasks.cpp b/src/platforms/posix/px4_layer/px4_posix_tasks.cpp
index c09845b79a..5a36313aed 100644
--- a/src/platforms/posix/px4_layer/px4_posix_tasks.cpp
+++ b/src/platforms/posix/px4_layer/px4_posix_tasks.cpp
@@ -83,9 +83,9 @@ static void *entry_adapter ( void *ptr )
 
 	data->entry(data->argc, data->argv);
 	free(ptr);
-	PX4_DBG("Before px4_task_exit");
+	PX4_DEBUG("Before px4_task_exit");
 	px4_task_exit(0); 
-	PX4_DBG("After px4_task_exit");
+	PX4_DEBUG("After px4_task_exit");
 
 	return NULL;
 } 
@@ -231,7 +231,7 @@ void px4_task_exit(int ret)
 		PX4_ERR("px4_task_exit: self task not found!");
 	}
 	else {
-		PX4_DBG("px4_task_exit: %s", taskmap[i].name.c_str());
+		PX4_DEBUG("px4_task_exit: %s", taskmap[i].name.c_str());
 	}
 
 	pthread_exit((void *)(unsigned long)ret);
@@ -241,7 +241,7 @@ int px4_task_kill(px4_task_t id, int sig)
 {
 	int rv = 0;
 	pthread_t pid;
-	PX4_DBG("Called px4_task_kill %d", sig);
+	PX4_DEBUG("Called px4_task_kill %d", sig);
 
 	if (id < PX4_MAX_TASKS && taskmap[id].pid != 0)
 		pid = taskmap[id].pid;
@@ -271,3 +271,18 @@ void px4_show_tasks()
 		PX4_INFO("   No running tasks");
 
 }
+
+__BEGIN_DECLS
+const char *getprogname()
+{
+        pthread_t pid = pthread_self();
+	for (int i=0; i<PX4_MAX_TASKS; i++)
+	{
+		if (taskmap[i].isused && taskmap[i].pid == pid)
+		{
+			return taskmap[i].name.c_str();
+		}
+	}
+	return "Unknown App";
+}
+__END_DECLS
diff --git a/src/platforms/px4_log.h b/src/platforms/px4_log.h
index 7d6f602083..2dd849f24a 100644
--- a/src/platforms/px4_log.h
+++ b/src/platforms/px4_log.h
@@ -44,6 +44,8 @@ __BEGIN_DECLS
 extern void qurt_log(const char *fmt, ...);
 __END_DECLS
 
+#include <stdio.h>
+
 #define qurt_log(...)   {printf(__VA_ARGS__); printf("\n");}
 #define PX4_DBG(...)	qurt_log(__VA_ARGS__)
 #define PX4_DEBUG(...)	qurt_log(__VA_ARGS__)
@@ -52,18 +54,23 @@ __END_DECLS
 #define PX4_ERR(...)	{ qurt_log("ERROR file %s line %d:", __FILE__, __LINE__); qurt_log(__VA_ARGS__); }
 
 #elif defined(__PX4_LINUX)
-
-#if defined(__PX4_LINUX)
-#include <err.h>
-#else
-#include <systemlib/err.h>
-#endif
-
-#define PX4_DBG(...)	
-#define PX4_DEBUG(...)	
-#define PX4_INFO(...) 	warnx(__VA_ARGS__)
-#define PX4_WARN(...) 	warnx(__VA_ARGS__)
-#define PX4_ERR(...)	{ warnx("ERROR file %s line %d:", __FILE__, __LINE__); warnx(__VA_ARGS__); }
+#include <stdio.h>
+
+#define linux_log(level, ...)   { \
+	printf("%-5s ", level);\
+	printf(__VA_ARGS__);\
+	printf("\n");\
+}
+#define linux_log_verbose(level, ...)   { \
+	printf("%-5s ", level);\
+	printf(__VA_ARGS__);\
+	printf(" (file %s line %d)\n", __FILE__, __LINE__);\
+}
+//#define PX4_DEBUG(...)	{ }
+#define PX4_DEBUG(...) 	{ linux_log("DEBUG", __VA_ARGS__); }
+#define PX4_INFO(...) 	{ linux_log("INFO",  __VA_ARGS__); }
+#define PX4_WARN(...) 	{ linux_log_verbose("WARN",  __VA_ARGS__); }
+#define PX4_ERR(...)	{ linux_log_verbose("ERROR", __VA_ARGS__); }
 
 #elif defined(__PX4_ROS)
 
diff --git a/src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp b/src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp
index 7490f1528c..bbd1366ec2 100644
--- a/src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp
+++ b/src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp
@@ -264,7 +264,7 @@ void px4_show_tasks()
 	for (idx=0; idx < PX4_MAX_TASKS; idx++)
 	{
 		if (taskmap[idx].isused) {
-			PX4_INFO("   %-10s %u", taskmap[idx].name.c_str(), taskmap[idx].pid);
+			PX4_INFO("   %-10s %lu", taskmap[idx].name.c_str(), taskmap[idx].pid);
 			count++;
 		}
 	}
-- 
GitLab