diff --git a/boards/airmind/mindpx-v2/src/init.c b/boards/airmind/mindpx-v2/src/init.c
index de16f44165c895f49a4e398d45f33b5f76ba09b5..e9f840b05fd7839c419c57211942c3eac8f9bb9e 100644
--- a/boards/airmind/mindpx-v2/src/init.c
+++ b/boards/airmind/mindpx-v2/src/init.c
@@ -77,24 +77,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -237,7 +219,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	/* set up the serial DMA polling */
@@ -270,7 +252,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi4 = px4_spibus_initialize(4);
 
 	if (!spi4) {
-		message("[boot] FAILED to initialize SPI port 4\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 4\n");
 		board_autoled_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -290,7 +272,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi1 = stm32_spibus_initialize(1);
 
 	if (!spi1) {
-		message("[boot] FAILED to initialize SPI port 1\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 1\n");
 		board_autoled_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -320,8 +302,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
 
 	if (!sdio) {
-		message("[boot] Failed to initialize SDIO slot %d\n",
-			CONFIG_NSH_MMCSDSLOTNO);
+		syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n",
+		       CONFIG_NSH_MMCSDSLOTNO);
 		return -ENODEV;
 	}
 
@@ -329,7 +311,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
 
 	if (ret != OK) {
-		message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+		syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
 		return ret;
 	}
 
diff --git a/boards/airmind/mindpx-v2/src/spi.c b/boards/airmind/mindpx-v2/src/spi.c
index 83cdb9f68eb51129b49a25e5305659bea34a26b3..123c9fd4da35f50a804e37c83d560e819fff0212 100644
--- a/boards/airmind/mindpx-v2/src/spi.c
+++ b/boards/airmind/mindpx-v2/src/spi.c
@@ -54,7 +54,6 @@
 #include <chip.h>
 #include <stm32.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /************************************************************************************
  * Public Functions
@@ -208,7 +207,7 @@ __EXPORT void board_spi_reset(int ms)
 	//
 	/* wait for the sensor rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 	//
 	//        /* re-enable power */
 	//
diff --git a/boards/atmel/same70xplained/src/init.c b/boards/atmel/same70xplained/src/init.c
index 19a96ebe40b844923b6d6f23cec825f0aff72d7f..0e26d6e1a7e271d36a4bb122c1adb3ef60d64017 100644
--- a/boards/atmel/same70xplained/src/init.c
+++ b/boards/atmel/same70xplained/src/init.c
@@ -80,24 +80,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(LOG_NOTICE, __VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -239,7 +221,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 
@@ -253,7 +235,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi0 = px4_spibus_initialize(PX4_SPI_BUS_SENSORS);
 
 	if (!spi0) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
 		board_autoled_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -285,8 +267,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
 
 	if (!sdio) {
-		message("[boot] Failed to initialize SDIO slot %d\n",
-			CONFIG_NSH_MMCSDSLOTNO);
+		syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n",
+		       CONFIG_NSH_MMCSDSLOTNO);
 		return -ENODEV;
 	}
 
@@ -294,7 +276,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
 
 	if (ret != OK) {
-		message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+		syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
 		return ret;
 	}
 
diff --git a/boards/auav/x21/src/init.c b/boards/auav/x21/src/init.c
index 069a32d2da092e000ee45e3419113c15e0c0c728..65e6fa7306abf8a53b934c670729a283f322276f 100644
--- a/boards/auav/x21/src/init.c
+++ b/boards/auav/x21/src/init.c
@@ -78,24 +78,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -160,7 +142,7 @@ __EXPORT void board_peripheral_reset(int ms)
 
 	/* wait for the peripheral rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
@@ -257,7 +239,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	/* set up the serial DMA polling */
@@ -290,7 +272,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi1 = px4_spibus_initialize(1);
 
 	if (!spi1) {
-		message("[boot] FAILED to initialize SPI port 1\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 1\n");
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -309,7 +291,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi2 = px4_spibus_initialize(2);
 
 	if (!spi2) {
-		message("[boot] FAILED to initialize SPI port 2\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 2\n");
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -330,8 +312,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
 
 	if (!sdio) {
-		message("[boot] Failed to initialize SDIO slot %d\n",
-			CONFIG_NSH_MMCSDSLOTNO);
+		syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n",
+		       CONFIG_NSH_MMCSDSLOTNO);
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -340,7 +322,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
 
 	if (ret != OK) {
-		message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+		syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
 		led_on(LED_AMBER);
 		return ret;
 	}
diff --git a/boards/auav/x21/src/spi.c b/boards/auav/x21/src/spi.c
index eaf43a812a3c17d21bc23d8fe6a4bd9c60722a00..52d14291b3d57068f10f4029a4a8cd0a3b34ab9e 100644
--- a/boards/auav/x21/src/spi.c
+++ b/boards/auav/x21/src/spi.c
@@ -55,7 +55,6 @@
 #include <chip.h>
 #include <stm32.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 
 /************************************************************************************
@@ -176,7 +175,7 @@ __EXPORT void board_spi_reset(int ms)
 
 	/* wait for the sensor rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
diff --git a/boards/av/x-v1/src/spi.c b/boards/av/x-v1/src/spi.c
index 6f893684a202ea7717bb761c5f85e86c635cec87..d1fe890255a3a9e770ecb098fb677e12bb806854 100644
--- a/boards/av/x-v1/src/spi.c
+++ b/boards/av/x-v1/src/spi.c
@@ -57,7 +57,6 @@
 #include <chip.h>
 #include <stm32_gpio.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /****************************************************************************
  * Pre-Processor Definitions
diff --git a/boards/bitcraze/crazyflie/src/init.c b/boards/bitcraze/crazyflie/src/init.c
index 45b317ea6cec79065b5f888699d664431dae711e..14f786d4ba3f5369cabf2260e4bea31c1321a4c9 100644
--- a/boards/bitcraze/crazyflie/src/init.c
+++ b/boards/bitcraze/crazyflie/src/init.c
@@ -73,24 +73,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
diff --git a/boards/bitcraze/crazyflie/src/spi.c b/boards/bitcraze/crazyflie/src/spi.c
index 40df3620be202cddbc837ec02acf75205c2d1993..1be0660c99144d3cd0c5c46dad89b3bfe5fbd0b4 100644
--- a/boards/bitcraze/crazyflie/src/spi.c
+++ b/boards/bitcraze/crazyflie/src/spi.c
@@ -19,7 +19,6 @@
 #include <chip.h>
 #include <stm32_gpio.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /****************************************************************************
  * Pre-Processor Definitions
@@ -147,7 +146,7 @@ __EXPORT void board_spi_reset(int ms)
 
 	/* wait for the sensor rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* wait a bit before starting SPI, different times didn't influence results */
 	usleep(100);
diff --git a/boards/emlid/navio2/navio_adc/navio_adc.cpp b/boards/emlid/navio2/navio_adc/navio_adc.cpp
index 57c3c5f1370f14210e186bbb80375adacca105d4..6614a65eedef9d1230a9d4a9d4e487259e31caa7 100644
--- a/boards/emlid/navio2/navio_adc/navio_adc.cpp
+++ b/boards/emlid/navio2/navio_adc/navio_adc.cpp
@@ -52,6 +52,7 @@
 #include <stdio.h>
 #include <poll.h>
 #include <string.h>
+#include <stdlib.h>
 
 #define ADC_BASE_DEV_PATH "/dev/adc"
 #define ADC_SYSFS_PATH "/sys/kernel/rcio/adc/ch0"
diff --git a/boards/emlid/navio2/navio_rgbled/navio_rgbled.cpp b/boards/emlid/navio2/navio_rgbled/navio_rgbled.cpp
index 4a67dea4658f5688d98e0a3e4ff35ef6f9a8c68d..5241a4009707fef1b6c15b3ce9224092a6842887 100644
--- a/boards/emlid/navio2/navio_rgbled/navio_rgbled.cpp
+++ b/boards/emlid/navio2/navio_rgbled/navio_rgbled.cpp
@@ -34,6 +34,8 @@
 #include <px4_posix.h>
 #include <drivers/drv_led.h>
 
+#include <string.h>
+
 #include "navio_rgbled.h"
 
 #define RGBLED_BASE_DEVICE_PATH "/dev/rgbled"
diff --git a/boards/emlid/navio2/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp b/boards/emlid/navio2/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp
index 18081a09ff440d704db78fecb100c99315829718..9233525feb3b6f3544b0cd4353cec496c8b5d3d8 100644
--- a/boards/emlid/navio2/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp
+++ b/boards/emlid/navio2/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp
@@ -38,6 +38,8 @@
 #include <stdio.h>
 #include <stdint.h>
 #include <unistd.h>
+#include <string.h>
+#include <stdlib.h>
 
 #include <px4_config.h>
 #include <px4_workqueue.h>
diff --git a/boards/gumstix/aerocore2/src/init.c b/boards/gumstix/aerocore2/src/init.c
index ad1bf89b8cee7837a27167399a7e832772d547cf..c77e334b1825fb894e9e98bb74cea8572970a35f 100644
--- a/boards/gumstix/aerocore2/src/init.c
+++ b/boards/gumstix/aerocore2/src/init.c
@@ -74,24 +74,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) lowsyslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message lowsyslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -125,7 +107,7 @@ __EXPORT void board_peripheral_reset(int ms)
 
 	/* wait for the peripheral rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 	/* switch the peripheral rail back on */
@@ -207,7 +189,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	/* set up the serial DMA polling */
@@ -236,7 +218,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi3 = px4_spibus_initialize(3);
 
 	if (!spi3) {
-		message("[boot] FAILED to initialize SPI port 3\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 3\n");
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -255,7 +237,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi4 = px4_spibus_initialize(4);
 
 	if (!spi4) {
-		message("[boot] FAILED to initialize SPI port 4\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 4\n");
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
diff --git a/boards/gumstix/aerocore2/src/spi.c b/boards/gumstix/aerocore2/src/spi.c
index 4695a712ecbe17e8412fd39e7c255ec9062e7635..00c73debd6f1f193180d7a7a33b56675a9923598 100644
--- a/boards/gumstix/aerocore2/src/spi.c
+++ b/boards/gumstix/aerocore2/src/spi.c
@@ -54,7 +54,6 @@
 #include <chip.h>
 #include <stm32.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /************************************************************************************
  * Public Functions
@@ -203,7 +202,7 @@ __EXPORT void board_spi_reset(int ms)
 
 	/* wait for the sensor rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* wait a bit before starting SPI, different times didn't influence results */
 	usleep(100);
diff --git a/boards/intel/aerofc-v1/src/init.c b/boards/intel/aerofc-v1/src/init.c
index b4ae07bb0a1ef3b5e32c65bc6df600da1bd499fe..ee45c6e5bc648ac97a5299d96e2148b7acc51b77 100644
--- a/boards/intel/aerofc-v1/src/init.c
+++ b/boards/intel/aerofc-v1/src/init.c
@@ -79,24 +79,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -226,7 +208,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	result = parameter_flashfs_init(params_sector_map, NULL, 0);
 
 	if (result != OK) {
-		message("[boot] FAILED to init params in FLASH %d\n", result);
+		syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
diff --git a/boards/nxp/fmuk66-v3/src/init.c b/boards/nxp/fmuk66-v3/src/init.c
index 9699f32291af60fc7d643f3e0a8bc9b1fb218c06..e5a447062935594963917205f43b6807f7de5b33 100644
--- a/boards/nxp/fmuk66-v3/src/init.c
+++ b/boards/nxp/fmuk66-v3/src/init.c
@@ -79,24 +79,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -204,7 +186,7 @@ __EXPORT void board_peripheral_reset(int ms)
 
 	/* wait for the peripheral rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
@@ -282,7 +264,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	/* set up the serial DMA polling */
diff --git a/boards/nxp/fmuk66-v3/src/sdhc.c b/boards/nxp/fmuk66-v3/src/sdhc.c
index 3b3ce0649978593bc4268edd683c022b036cc7c8..1f39b29529693efec90e3f8e642fd1f002edb6f3 100644
--- a/boards/nxp/fmuk66-v3/src/sdhc.c
+++ b/boards/nxp/fmuk66-v3/src/sdhc.c
@@ -208,7 +208,7 @@ int fmuk66_sdhc_initialize(void)
 		return ret;
 	}
 
-	syslog(LOG_INFO, "Successfully bound SDHC to the MMC/SD driver\n");
+	syslog(LOG_ERR, "Successfully bound SDHC to the MMC/SD driver\n");
 
 	/* Handle the initial card state */
 
diff --git a/boards/nxp/fmuk66-v3/src/spi.c b/boards/nxp/fmuk66-v3/src/spi.c
index f5a6a48f0bab858564af279536a072e581671f8b..33de9a2140e80cf6fa0170bdf458270b86240b56 100644
--- a/boards/nxp/fmuk66-v3/src/spi.c
+++ b/boards/nxp/fmuk66-v3/src/spi.c
@@ -51,25 +51,9 @@
 #include "chip.h"
 #include <kinetis.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 #include <systemlib/px4_macros.h>
 
-#if defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI1) || \
-	defined(CONFIG_KINETIS_SPI2)
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
+#if defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI1) || defined(CONFIG_KINETIS_SPI2)
 
 /* Define CS GPIO array */
 static const uint32_t spi0selects_gpio[] = PX4_MEMORY_BUS_CS_GPIO;
@@ -208,7 +192,7 @@ __EXPORT int fmuk66_spi_bus_initialize(void)
 	spi_sensors = px4_spibus_initialize(PX4_SPI_BUS_SENSORS);
 
 	if (!spi_sensors) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
 		return -ENODEV;
 	}
 
@@ -228,7 +212,7 @@ __EXPORT int fmuk66_spi_bus_initialize(void)
 	spi_memory = px4_spibus_initialize(PX4_SPI_BUS_MEMORY);
 
 	if (!spi_memory) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_MEMORY);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_MEMORY);
 		return -ENODEV;
 	}
 
@@ -248,7 +232,7 @@ __EXPORT int fmuk66_spi_bus_initialize(void)
 	spi_ext = px4_spibus_initialize(PX4_SPI_BUS_EXTERNAL);
 
 	if (!spi_ext) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL);
 		return -ENODEV;
 	}
 
diff --git a/boards/omnibus/f4sd/src/init.c b/boards/omnibus/f4sd/src/init.c
index 846407ca73583e6cf40e62abbe58feb8e4d0f33f..03f7e438b8856c40ed50ef6359b5b28b926687ef 100644
--- a/boards/omnibus/f4sd/src/init.c
+++ b/boards/omnibus/f4sd/src/init.c
@@ -82,24 +82,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -262,7 +244,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	/* set up the serial DMA polling */
@@ -297,7 +279,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi1 = stm32_spibus_initialize(1);
 
 	if (!spi1) {
-		message("[boot] FAILED to initialize SPI port 1\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 1\n");
 		led_on(LED_BLUE);
 		return -ENODEV;
 	}
@@ -314,7 +296,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi2 = stm32_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO);
 
 	if (!spi2) {
-		message("[boot] FAILED to initialize SPI port %d\n", CONFIG_NSH_MMCSDSPIPORTNO);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", CONFIG_NSH_MMCSDSPIPORTNO);
 		led_on(LED_BLUE);
 		return -ENODEV;
 	}
@@ -324,7 +306,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	if (result != OK) {
 		led_on(LED_BLUE);
-		message("[boot] FAILED to bind SPI port 2 to the MMCSD driver\n");
+		syslog(LOG_ERR, "[boot] FAILED to bind SPI port 2 to the MMCSD driver\n");
 		return -ENODEV;
 	}
 
@@ -335,7 +317,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi3 = stm32_spibus_initialize(3);
 
 	if (!spi3) {
-		message("[boot] FAILED to initialize SPI port 3\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 3\n");
 		led_on(LED_BLUE);
 		return -ENODEV;
 	}
@@ -362,7 +344,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	result = parameter_flashfs_init(params_sector_map, NULL, 0);
 
 	if (result != OK) {
-		message("[boot] FAILED to init params in FLASH %d\n", result);
+		syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
diff --git a/boards/omnibus/f4sd/src/spi.c b/boards/omnibus/f4sd/src/spi.c
index f40a8961ca0e843931a1ef775b2e8aab42c42e96..16588695b688b7e3adbc02d5539803c1137226eb 100644
--- a/boards/omnibus/f4sd/src/spi.c
+++ b/boards/omnibus/f4sd/src/spi.c
@@ -55,7 +55,6 @@
 #include <chip.h>
 #include <stm32.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /************************************************************************************
  * Public Functions
diff --git a/boards/parrot/bebop/flow/bebop_flow.cpp b/boards/parrot/bebop/flow/bebop_flow.cpp
index e99b75c846d9702a791299ce8496955a8e8ecec6..f26933302c7f94c65040778c1d07c5a9826bac50 100644
--- a/boards/parrot/bebop/flow/bebop_flow.cpp
+++ b/boards/parrot/bebop/flow/bebop_flow.cpp
@@ -38,7 +38,9 @@
  * an optical flow computation.
  */
 
+#include <stdlib.h>
 #include <stdint.h>
+#include <string.h>
 
 #include <px4_tasks.h>
 #include <px4_getopt.h>
diff --git a/boards/parrot/bebop/flow/video_device.cpp b/boards/parrot/bebop/flow/video_device.cpp
index 80bb06d83e3fdd1ca0cc565c13650c3ca6ab0fca..35c17420a0fec2bdafb15d761429ac2aa3614872 100644
--- a/boards/parrot/bebop/flow/video_device.cpp
+++ b/boards/parrot/bebop/flow/video_device.cpp
@@ -40,6 +40,8 @@
 
 #include "video_device.h"
 
+#include <stdlib.h>
+
 #include <sys/stat.h>
 #include <sys/ioctl.h>
 #include <sys/mman.h>
diff --git a/boards/px4/fmu-v2/default.cmake b/boards/px4/fmu-v2/default.cmake
index 92f958ec45d0310df36195eb1fc68f64fc260eaf..c83e2ae975a720808017cd7647812a1732827ace 100644
--- a/boards/px4/fmu-v2/default.cmake
+++ b/boards/px4/fmu-v2/default.cmake
@@ -3,6 +3,7 @@ px4_add_board(
 	PLATFORM nuttx
 	VENDOR px4
 	MODEL fmu-v2
+	LABEL default
 	TOOLCHAIN arm-none-eabi
 	ARCHITECTURE cortex-m4
 	ROMFSROOT px4fmu_common
diff --git a/boards/px4/fmu-v2/src/init.c b/boards/px4/fmu-v2/src/init.c
index c61a6467e503736ef9946f37a4a85bff207fe4e1..f96ca3ccb61e96ce43ed8e6ec56803b81eb86637 100644
--- a/boards/px4/fmu-v2/src/init.c
+++ b/boards/px4/fmu-v2/src/init.c
@@ -47,7 +47,6 @@
 
 #include <px4_config.h>
 #include <px4_tasks.h>
-#include <px4_time.h>
 
 #include <stdbool.h>
 #include <stdio.h>
@@ -79,24 +78,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -130,8 +111,8 @@ __EXPORT void board_peripheral_reset(int ms)
 	stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 1);
 
 	/* wait for the peripheral rail to reach GND */
-	px4_usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	usleep(ms * 1000);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
@@ -382,7 +363,7 @@ static struct sdio_dev_s *sdio;
 __EXPORT int board_app_initialize(uintptr_t arg)
 {
 	/* Ensure the power is on 1 ms before we drive the GPIO pins */
-	px4_usleep(1000);
+	usleep(1000);
 
 	if (OK == determin_hw_version(&hw_version, & hw_revision)) {
 		switch (hw_version) {
@@ -416,7 +397,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 				hw_version = HW_VER_FMUV3_STATE;
 				hw_type[1]++;
 				hw_type[2] = '0';
-				message("\nPixhack V3 detected, forcing to fmu-v3");
+				syslog(LOG_INFO, "\nPixhack V3 detected, forcing to fmu-v3");
 
 			} else {
 
@@ -431,12 +412,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 			/* questionable px4_fmu-v2 hardware, try forcing regular FMUv2 (not much else we can do) */
 
-			message("\nbad version detected, forcing to fmu-v2");
+			syslog(LOG_ERR, "\nbad version detected, forcing to fmu-v2");
 			hw_version = HW_VER_FMUV2_STATE;
 			break;
 		}
 
-		message("\nFMUv2 ver 0x%1X : Rev %x %s\n", hw_version, hw_revision, hw_type);
+		syslog(LOG_DEBUG, "\nFMUv2 ver 0x%1X : Rev %x %s\n", hw_version, hw_revision, hw_type);
 	}
 
 	/* configure SPI interfaces */
@@ -447,7 +428,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	/* set up the serial DMA polling */
@@ -480,7 +461,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi1 = stm32_spibus_initialize(PX4_SPI_BUS_SENSORS);
 
 	if (!spi1) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -496,7 +477,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi2 = stm32_spibus_initialize(PX4_SPI_BUS_RAMTRON);
 
 	if (!spi2) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -512,7 +493,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi4 = stm32_spibus_initialize(PX4_SPI_BUS_EXT);
 
 	if (!spi4) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT);
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -529,7 +510,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	if (!sdio) {
 		led_on(LED_AMBER);
-		message("[boot] Failed to initialize SDIO slot %d\n", CONFIG_NSH_MMCSDSLOTNO);
+		syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", CONFIG_NSH_MMCSDSLOTNO);
 		return -ENODEV;
 	}
 
@@ -538,7 +519,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	if (ret != OK) {
 		led_on(LED_AMBER);
-		message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+		syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
 		return ret;
 	}
 
diff --git a/boards/px4/fmu-v2/src/spi.c b/boards/px4/fmu-v2/src/spi.c
index fc2233f30bf5d6e3fbcdc0a1b61a710333a289a5..4df601639df1edd020fd9bc6725549b64483a3f2 100644
--- a/boards/px4/fmu-v2/src/spi.c
+++ b/boards/px4/fmu-v2/src/spi.c
@@ -41,7 +41,6 @@
  * Included Files
  ************************************************************************************/
 
-#include <px4_time.h>
 #include <px4_config.h>
 
 #include <stdint.h>
@@ -56,7 +55,6 @@
 #include <chip.h>
 #include <stm32.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /************************************************************************************
  * Public Functions
@@ -421,8 +419,8 @@ __EXPORT void board_spi_reset(int ms)
 	stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0);
 
 	/* wait for the sensor rail to reach GND */
-	px4_usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	usleep(ms * 1000);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
@@ -430,7 +428,7 @@ __EXPORT void board_spi_reset(int ms)
 	stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1);
 
 	/* wait a bit before starting SPI, different times didn't influence results */
-	px4_usleep(100);
+	usleep(100);
 
 	/* reconfigure the SPI pins */
 	stm32_configgpio(GPIO_SPI1_SCK);
diff --git a/boards/px4/fmu-v3/nuttx-config/include/board.h b/boards/px4/fmu-v3/nuttx-config/include/board.h
index fd26e2cbca8927ab240d6eea78ea66d85625a89a..be9b54dc24f3a81773a4caf1bfdc0304294c2f68 100644
--- a/boards/px4/fmu-v3/nuttx-config/include/board.h
+++ b/boards/px4/fmu-v3/nuttx-config/include/board.h
@@ -259,13 +259,13 @@
 
 #define GPIO_I2C1_SCL    GPIO_I2C1_SCL_2
 #define GPIO_I2C1_SDA    GPIO_I2C1_SDA_2
-#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
-#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
+#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
+#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
 
 #define GPIO_I2C2_SCL    GPIO_I2C2_SCL_1
 #define GPIO_I2C2_SDA    GPIO_I2C2_SDA_1
-#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10)
-#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11)
+#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
 
 /* SPI
  *
diff --git a/boards/px4/fmu-v3/src/init.c b/boards/px4/fmu-v3/src/init.c
index f39dd09a3e68e5827b066839e7d38ab386ee933a..f96ca3ccb61e96ce43ed8e6ec56803b81eb86637 100644
--- a/boards/px4/fmu-v3/src/init.c
+++ b/boards/px4/fmu-v3/src/init.c
@@ -78,24 +78,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -130,7 +112,7 @@ __EXPORT void board_peripheral_reset(int ms)
 
 	/* wait for the peripheral rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
@@ -415,7 +397,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 				hw_version = HW_VER_FMUV3_STATE;
 				hw_type[1]++;
 				hw_type[2] = '0';
-				message("\nPixhack V3 detected, forcing to fmu-v3");
+				syslog(LOG_INFO, "\nPixhack V3 detected, forcing to fmu-v3");
 
 			} else {
 
@@ -430,12 +412,12 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 			/* questionable px4_fmu-v2 hardware, try forcing regular FMUv2 (not much else we can do) */
 
-			message("\nbad version detected, forcing to fmu-v2");
+			syslog(LOG_ERR, "\nbad version detected, forcing to fmu-v2");
 			hw_version = HW_VER_FMUV2_STATE;
 			break;
 		}
 
-		message("\nFMUv2 ver 0x%1X : Rev %x %s\n", hw_version, hw_revision, hw_type);
+		syslog(LOG_DEBUG, "\nFMUv2 ver 0x%1X : Rev %x %s\n", hw_version, hw_revision, hw_type);
 	}
 
 	/* configure SPI interfaces */
@@ -446,7 +428,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	/* set up the serial DMA polling */
@@ -479,7 +461,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi1 = stm32_spibus_initialize(PX4_SPI_BUS_SENSORS);
 
 	if (!spi1) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -495,7 +477,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi2 = stm32_spibus_initialize(PX4_SPI_BUS_RAMTRON);
 
 	if (!spi2) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -511,7 +493,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi4 = stm32_spibus_initialize(PX4_SPI_BUS_EXT);
 
 	if (!spi4) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT);
 		led_on(LED_AMBER);
 		return -ENODEV;
 	}
@@ -528,7 +510,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	if (!sdio) {
 		led_on(LED_AMBER);
-		message("[boot] Failed to initialize SDIO slot %d\n", CONFIG_NSH_MMCSDSLOTNO);
+		syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", CONFIG_NSH_MMCSDSLOTNO);
 		return -ENODEV;
 	}
 
@@ -537,7 +519,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	if (ret != OK) {
 		led_on(LED_AMBER);
-		message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+		syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
 		return ret;
 	}
 
diff --git a/boards/px4/fmu-v3/src/spi.c b/boards/px4/fmu-v3/src/spi.c
index ca29b39c32ba114b41299de5b4819012957d4650..4df601639df1edd020fd9bc6725549b64483a3f2 100644
--- a/boards/px4/fmu-v3/src/spi.c
+++ b/boards/px4/fmu-v3/src/spi.c
@@ -55,7 +55,6 @@
 #include <chip.h>
 #include <stm32.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /************************************************************************************
  * Public Functions
@@ -421,7 +420,7 @@ __EXPORT void board_spi_reset(int ms)
 
 	/* wait for the sensor rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
diff --git a/boards/px4/fmu-v4/src/init.c b/boards/px4/fmu-v4/src/init.c
index a1c35cc268d67313c6479e31291b6c816bb03ab9..c57cd29466fe76f62fdbcdad0f7b194d6e84f3ec 100644
--- a/boards/px4/fmu-v4/src/init.c
+++ b/boards/px4/fmu-v4/src/init.c
@@ -79,24 +79,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /**
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -135,7 +117,7 @@ __EXPORT void board_peripheral_reset(int ms)
 
 	// Wait for the peripheral rail to reach GND.
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	// Re-enable power.
 	// Switch the peripheral rail back on.
@@ -271,7 +253,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	// Configure the DMA allocator.
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	// Set up the serial DMA polling.
@@ -311,7 +293,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi1 = stm32_spibus_initialize(1);
 
 	if (!spi1) {
-		message("[boot] FAILED to initialize SPI port 1\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 1\n");
 		led_on(LED_RED);
 		return -ENODEV;
 	}
@@ -330,7 +312,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi2 = stm32_spibus_initialize(2);
 
 	if (!spi2) {
-		message("[boot] FAILED to initialize SPI port 2\n");
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 2\n");
 		led_on(LED_RED);
 		return -ENODEV;
 	}
@@ -354,8 +336,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	if (!sdio) {
 		led_on(LED_RED);
-		message("[boot] Failed to initialize SDIO slot %d\n",
-			CONFIG_NSH_MMCSDSLOTNO);
+		syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n",
+		       CONFIG_NSH_MMCSDSLOTNO);
 		return -ENODEV;
 	}
 
@@ -364,7 +346,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	if (ret != OK) {
 		led_on(LED_RED);
-		message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+		syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
 		return ret;
 	}
 
diff --git a/boards/px4/fmu-v4/src/spi.c b/boards/px4/fmu-v4/src/spi.c
index 873cac955689abadac381b5196a592ba981584d8..f376f09231d6515b41d4962b0757ab6cbf958115 100644
--- a/boards/px4/fmu-v4/src/spi.c
+++ b/boards/px4/fmu-v4/src/spi.c
@@ -55,7 +55,6 @@
 #include <chip.h>
 #include <stm32.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /************************************************************************************
  * Public Functions
@@ -223,7 +222,7 @@ __EXPORT void board_spi_reset(int ms)
 
 	/* wait for the sensor rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
diff --git a/boards/px4/fmu-v4pro/src/init.c b/boards/px4/fmu-v4pro/src/init.c
index 104f1abc43f31bd53dd01ae8afad9cbef9d5e87a..8077cab32d3a90516a3a8dac38efa046ad50c1dc 100644
--- a/boards/px4/fmu-v4pro/src/init.c
+++ b/boards/px4/fmu-v4pro/src/init.c
@@ -79,24 +79,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -137,7 +119,7 @@ __EXPORT void board_peripheral_reset(int ms)
 
 	/* wait for the peripheral rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
@@ -307,7 +289,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	/* set up the serial DMA polling */
@@ -342,7 +324,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi1 = stm32_spibus_initialize(PX4_SPI_BUS_SENSORS);
 
 	if (!spi1) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
 		led_on(LED_RED);
 		return -ENODEV;
 	}
@@ -363,7 +345,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi2 = stm32_spibus_initialize(PX4_SPI_BUS_RAMTRON);
 
 	if (!spi2) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
 		led_on(LED_RED);
 		return -ENODEV;
 	}
@@ -382,7 +364,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi5 = stm32_spibus_initialize(PX4_SPI_BUS_EXT0);
 
 	if (!spi5) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT0);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT0);
 		led_on(LED_RED);
 		return -ENODEV;
 	}
@@ -398,7 +380,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	spi6 = stm32_spibus_initialize(PX4_SPI_BUS_EXT1);
 
 	if (!spi6) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT1);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT1);
 		led_on(LED_RED);
 		return -ENODEV;
 	}
@@ -416,8 +398,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	if (!sdio) {
 		led_on(LED_RED);
-		message("[boot] Failed to initialize SDIO slot %d\n",
-			CONFIG_NSH_MMCSDSLOTNO);
+		syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n",
+		       CONFIG_NSH_MMCSDSLOTNO);
 		return -ENODEV;
 	}
 
@@ -426,7 +408,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 
 	if (ret != OK) {
 		led_on(LED_RED);
-		message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+		syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
 		return ret;
 	}
 
diff --git a/boards/px4/fmu-v4pro/src/spi.c b/boards/px4/fmu-v4pro/src/spi.c
index 3cab587a59cafabe57399f052a8a47e16223e5ed..262a81d305ff7908ae33b52e74d0a183c6797aa3 100644
--- a/boards/px4/fmu-v4pro/src/spi.c
+++ b/boards/px4/fmu-v4pro/src/spi.c
@@ -55,7 +55,6 @@
 #include <chip.h>
 #include <stm32.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /************************************************************************************
  * Public Functions
@@ -258,7 +257,7 @@ __EXPORT void board_spi_reset(int ms)
 
 	/* wait for the sensor rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
diff --git a/boards/px4/fmu-v5/src/init.c b/boards/px4/fmu-v5/src/init.c
index eda68ebda947b4456363163cbb83c58ccf6159c6..d972ece0d1ed070b1079ef167fe30edcfc95aaae 100644
--- a/boards/px4/fmu-v5/src/init.c
+++ b/boards/px4/fmu-v5/src/init.c
@@ -162,7 +162,7 @@ __EXPORT void board_peripheral_reset(int ms)
 
 	/* wait for the peripheral rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
diff --git a/boards/px4/fmu-v5/src/spi.c b/boards/px4/fmu-v5/src/spi.c
index 083adc0de41036f51483ac99f170c6c82cd89b27..b7a610cc60f96029a9fa2ba178124edd9cee625d 100644
--- a/boards/px4/fmu-v5/src/spi.c
+++ b/boards/px4/fmu-v5/src/spi.c
@@ -57,7 +57,6 @@
 #include <chip.h>
 #include <stm32_gpio.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /****************************************************************************
  * Pre-Processor Definitions
@@ -476,7 +475,7 @@ __EXPORT void board_spi_reset(int ms)
 
 	/* wait for the sensor rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
diff --git a/boards/px4/io-v2/src/init.c b/boards/px4/io-v2/src/init.c
index 12c0db3fc62f5572e2bd17830713903bf4b6bb32..f7ba3635803c1bbd44986098af0b9c9cc9b06692 100644
--- a/boards/px4/io-v2/src/init.c
+++ b/boards/px4/io-v2/src/init.c
@@ -63,24 +63,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /****************************************************************************
  * Protected Functions
  ****************************************************************************/
diff --git a/boards/stm/32f4discovery/src/init.c b/boards/stm/32f4discovery/src/init.c
index e84b102581ebc90481445488502739ab4e09698d..eae7cf41b02464e90760a3ece1fcf4952cfb7bd3 100644
--- a/boards/stm/32f4discovery/src/init.c
+++ b/boards/stm/32f4discovery/src/init.c
@@ -75,24 +75,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /****************************************************************************
  * Protected Functions
  ****************************************************************************/
diff --git a/boards/stm/nucleo-F767ZI/src/init.c b/boards/stm/nucleo-F767ZI/src/init.c
index 8f43bd5717405675652fe299b1481506249e9b46..347bbf786d924c408a7c9c1c756221bffd7dc349 100644
--- a/boards/stm/nucleo-F767ZI/src/init.c
+++ b/boards/stm/nucleo-F767ZI/src/init.c
@@ -80,24 +80,6 @@
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /*
  * Ideally we'd be able to get these from up_internal.h,
  * but since we want to be able to disable the NuttX use
@@ -136,7 +118,7 @@ __EXPORT void board_peripheral_reset(int ms)
 
 	/* wait for the peripheral rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
@@ -238,7 +220,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
 	/* configure the DMA allocator */
 
 	if (board_dma_alloc_init() < 0) {
-		message("DMA alloc FAILED");
+		syslog(LOG_ERR, "DMA alloc FAILED\n");
 	}
 
 	/* set up the serial DMA polling */
diff --git a/boards/stm/nucleo-F767ZI/src/sdio.c b/boards/stm/nucleo-F767ZI/src/sdio.c
index a60a4df6b949e67462708b12fc69d8374aae631c..c06e515e09f9d954c6e6465b21dfcfec294fb5a7 100644
--- a/boards/stm/nucleo-F767ZI/src/sdio.c
+++ b/boards/stm/nucleo-F767ZI/src/sdio.c
@@ -58,23 +58,6 @@
  * Pre-processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /* Card detections requires card support and a card detection GPIO */
 
 #define HAVE_NCD   1
@@ -157,7 +140,7 @@ int stm32_sdio_initialize(void)
 	sdio_dev = sdio_initialize(SDIO_SLOTNO);
 
 	if (!sdio_dev) {
-		message("[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
+		syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
 		return -ENODEV;
 	}
 
@@ -168,7 +151,7 @@ int stm32_sdio_initialize(void)
 	ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
 
 	if (ret != OK) {
-		message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+		syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
 		return ret;
 	}
 
diff --git a/boards/stm/nucleo-F767ZI/src/spi.c b/boards/stm/nucleo-F767ZI/src/spi.c
index 9f34b6d5c1044303845ffb20d2054fbb2f2e9670..b7b3388590b3a1894e38c812b7ca3ead96c50d13 100644
--- a/boards/stm/nucleo-F767ZI/src/spi.c
+++ b/boards/stm/nucleo-F767ZI/src/spi.c
@@ -56,30 +56,11 @@
 #include <chip.h>
 #include <stm32_gpio.h>
 #include "board_config.h"
-#include <systemlib/err.h>
 
 /****************************************************************************
  * Pre-Processor Definitions
  ****************************************************************************/
 
-/* Configuration ************************************************************/
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-#  ifdef CONFIG_DEBUG
-#    define message(...) syslog(__VA_ARGS__)
-#  else
-#    define message(...) printf(__VA_ARGS__)
-#  endif
-#else
-#  ifdef CONFIG_DEBUG
-#    define message syslog
-#  else
-#    define message printf
-#  endif
-#endif
-
 /************************************************************************************
  * Public Functions
  ************************************************************************************/
@@ -140,7 +121,7 @@ __EXPORT int stm32_spi_bus_initialize(void)
 	spi_sensors = stm32_spibus_initialize(PX4_SPI_BUS_SENSORS);
 
 	if (!spi_sensors) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
 		return -ENODEV;
 	}
 
@@ -158,7 +139,7 @@ __EXPORT int stm32_spi_bus_initialize(void)
 	spi_fram = stm32_spibus_initialize(PX4_SPI_BUS_RAMTRON);
 
 	if (!spi_fram) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
 		return -ENODEV;
 	}
 
@@ -178,7 +159,7 @@ __EXPORT int stm32_spi_bus_initialize(void)
 	spi_baro = stm32_spibus_initialize(PX4_SPI_BUS_BARO);
 
 	if (!spi_baro) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_BARO);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_BARO);
 		return -ENODEV;
 	}
 
@@ -198,7 +179,7 @@ __EXPORT int stm32_spi_bus_initialize(void)
 	spi_icm = stm32_spibus_initialize(PX4_SPI_BUS_ICM);
 
 	if (!spi_icm) {
-		message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_ICM);
+		syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_ICM);
 		return -ENODEV;
 	}
 
@@ -371,7 +352,7 @@ __EXPORT void board_spi_reset(int ms)
 
 	/* wait for the sensor rail to reach GND */
 	usleep(ms * 1000);
-	warnx("reset done, %d ms", ms);
+	syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
 
 	/* re-enable power */
 
diff --git a/platforms/posix/src/main.cpp b/platforms/posix/src/main.cpp
index ff2acaf2bc4c508924b43cbfe115c10291bbcd15..3605f8884f9dd46548b66eced4d6651d76da3ef4 100644
--- a/platforms/posix/src/main.cpp
+++ b/platforms/posix/src/main.cpp
@@ -60,6 +60,7 @@
 #include <fcntl.h>
 #include <sys/stat.h>
 #include <stdlib.h>
+#include <string.h>
 
 #include <px4_time.h>
 #include <px4_log.h>
diff --git a/platforms/posix/src/px4_layer/px4_sem.cpp b/platforms/posix/src/px4_layer/px4_sem.cpp
index d60d1cb8132d0e27d3123acb1f6bfac5355d2d0c..e579c9222f64f85d9d2ff3c34971772fa330883d 100644
--- a/platforms/posix/src/px4_layer/px4_sem.cpp
+++ b/platforms/posix/src/px4_layer/px4_sem.cpp
@@ -148,7 +148,7 @@ int px4_sem_timedwait(px4_sem_t *s, const struct timespec *abstime)
 		const unsigned NAMELEN = 32;
 		char thread_name[NAMELEN] = {};
 		(void)pthread_getname_np(pthread_self(), thread_name, NAMELEN);
-		PX4_WARN("%s: px4_sem_timedwait failure: ret: %d, %s", thread_name, ret, strerror(ret));
+		PX4_WARN("%s: px4_sem_timedwait failure: ret: %d", thread_name, ret);
 	}
 
 	int mret = pthread_mutex_unlock(&(s->lock));
diff --git a/src/drivers/barometer/lps22hb/LPS22HB.hpp b/src/drivers/barometer/lps22hb/LPS22HB.hpp
index 559fa564bd36e99b9b94edadd0a830de0f97fda2..4ffa342dc7e894c2042987c709bcc982cdd0dc23 100644
--- a/src/drivers/barometer/lps22hb/LPS22HB.hpp
+++ b/src/drivers/barometer/lps22hb/LPS22HB.hpp
@@ -44,6 +44,7 @@
 #include <drivers/drv_hrt.h>
 #include <drivers/device/ringbuffer.h>
 #include <drivers/drv_device.h>
+#include <systemlib/err.h>
 
 #include <uORB/uORB.h>
 
diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp
index 0a033453c370ea8959892b68cacd87ae13b7b9ae..a9e856fc4f8a0e19d80ceaf467107e49d16e2a02 100644
--- a/src/drivers/batt_smbus/batt_smbus.cpp
+++ b/src/drivers/batt_smbus/batt_smbus.cpp
@@ -43,6 +43,8 @@
 
 #include "batt_smbus.h"
 
+#include <stdlib.h>
+
 extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]);
 
 struct work_s BATT_SMBUS::_work = {};
diff --git a/src/drivers/differential_pressure/ms5525/MS5525_main.cpp b/src/drivers/differential_pressure/ms5525/MS5525_main.cpp
index b718a7f5854dc37b822692d898dcd76570480605..e720a8c32a0ed8d9b60f6079b4cd0a2f17098508 100644
--- a/src/drivers/differential_pressure/ms5525/MS5525_main.cpp
+++ b/src/drivers/differential_pressure/ms5525/MS5525_main.cpp
@@ -35,6 +35,8 @@
 
 #include <px4_getopt.h>
 
+#include <stdlib.h>
+
 // Driver 'main' command.
 extern "C" __EXPORT int ms5525_airspeed_main(int argc, char *argv[]);
 
diff --git a/src/drivers/differential_pressure/sdp3x/SDP3X_main.cpp b/src/drivers/differential_pressure/sdp3x/SDP3X_main.cpp
index f6b65b08476b57a59b802a3eb4ecf565a74aff88..4bf604ca8719bd4fffd995a2e9e666c69aaeb7de 100644
--- a/src/drivers/differential_pressure/sdp3x/SDP3X_main.cpp
+++ b/src/drivers/differential_pressure/sdp3x/SDP3X_main.cpp
@@ -32,8 +32,11 @@
  ****************************************************************************/
 
 #include "SDP3X.hpp"
+
 #include <px4_getopt.h>
 
+#include <stdlib.h>
+
 // Driver 'main' command.
 extern "C" __EXPORT int sdp3x_airspeed_main(int argc, char *argv[]);
 
diff --git a/src/drivers/distance_sensor/leddar_one/leddar_one.cpp b/src/drivers/distance_sensor/leddar_one/leddar_one.cpp
index c0a9b68eca484e234650862c5207c14e491903d6..e85a55a02cf93825460c48e295a4ad9efe03693c 100644
--- a/src/drivers/distance_sensor/leddar_one/leddar_one.cpp
+++ b/src/drivers/distance_sensor/leddar_one/leddar_one.cpp
@@ -36,6 +36,7 @@
 #include <px4_getopt.h>
 #include <px4_defines.h>
 
+#include <stdlib.h>
 #include <string.h>
 #include <termios.h>
 
diff --git a/src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp b/src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp
index 209953fed7bdfd46de9124e59f9cb31c12223c60..be1281c6a704ed729eb86e717b00e8924eaa8936 100644
--- a/src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp
+++ b/src/drivers/distance_sensor/ll40ls/LidarLitePWM.cpp
@@ -122,7 +122,7 @@ void LidarLitePWM::print_info()
 	perf_print_counter(_sample_perf);
 	perf_print_counter(_read_errors);
 	perf_print_counter(_sensor_zero_resets);
-	warnx("poll interval:  %u ticks", getMeasureTicks());
+	PX4_INFO("poll interval:  %u ticks", getMeasureTicks());
 
 	print_message(_range);
 }
diff --git a/src/drivers/distance_sensor/ulanding/ulanding.cpp b/src/drivers/distance_sensor/ulanding/ulanding.cpp
index f357aa9143b1a6d9d734c1ebf35b0fa6282dd0a4..9c3e8703108cf358342b5f8a44084826130df81b 100644
--- a/src/drivers/distance_sensor/ulanding/ulanding.cpp
+++ b/src/drivers/distance_sensor/ulanding/ulanding.cpp
@@ -303,8 +303,6 @@ Radar::task_main_trampoline(int argc, char *argv[])
 int
 Radar::start()
 {
-	ASSERT(_task_handle == -1);
-
 	/* start the task */
 	_task_handle = px4_task_spawn_cmd("ulanding_radar",
 					  SCHED_DEFAULT,
diff --git a/src/drivers/imu/adis16477/ADIS16477.hpp b/src/drivers/imu/adis16477/ADIS16477.hpp
index 931a2f0efcaf5e50500d3d63d45703f7ca542ed1..0c5f875224b3af6b9176a24d327b6b66c577f1b7 100644
--- a/src/drivers/imu/adis16477/ADIS16477.hpp
+++ b/src/drivers/imu/adis16477/ADIS16477.hpp
@@ -49,6 +49,7 @@
 #include <lib/conversion/rotation.h>
 #include <perf/perf_counter.h>
 #include <ecl/geo/geo.h>
+#include <systemlib/err.h>
 
 #define ADIS16477_GYRO_DEFAULT_RATE					250
 #define ADIS16477_GYRO_DEFAULT_DRIVER_FILTER_FREQ	30
diff --git a/src/drivers/imu/bmi055/BMI055.hpp b/src/drivers/imu/bmi055/BMI055.hpp
index 7808d43e415db9390065f885ed656a460fb0b6e3..54fb3403c1be6a172d61210f06e5aaf2b917bc24 100644
--- a/src/drivers/imu/bmi055/BMI055.hpp
+++ b/src/drivers/imu/bmi055/BMI055.hpp
@@ -40,6 +40,7 @@
 #include <lib/perf/perf_counter.h>
 #include <px4_config.h>
 #include <systemlib/conversions.h>
+#include <systemlib/err.h>
 
 #define DIR_READ                0x80
 #define DIR_WRITE               0x00
diff --git a/src/drivers/imu/fxas21002c/fxas21002c.cpp b/src/drivers/imu/fxas21002c/fxas21002c.cpp
index d3f9bbfb2579db0af06c88ff40367579a2212828..31213bcba95b1317d4495aac1dfcf3efde3aa86d 100644
--- a/src/drivers/imu/fxas21002c/fxas21002c.cpp
+++ b/src/drivers/imu/fxas21002c/fxas21002c.cpp
@@ -73,6 +73,7 @@
 #include <mathlib/math/filter/LowPassFilter2p.hpp>
 #include <lib/conversion/rotation.h>
 #include <platforms/px4_getopt.h>
+#include <systemlib/err.h>
 
 /* SPI protocol address bits */
 #define DIR_READ(a)                     ((a) | (1 << 7))
diff --git a/src/drivers/imu/fxos8701cq/fxos8701cq.cpp b/src/drivers/imu/fxos8701cq/fxos8701cq.cpp
index b9f558062958c382cfd8ef530ecc1d8ca7d45d86..c3d7876af83672117fce011d4db804b86c255055 100644
--- a/src/drivers/imu/fxos8701cq/fxos8701cq.cpp
+++ b/src/drivers/imu/fxos8701cq/fxos8701cq.cpp
@@ -77,6 +77,7 @@
 #include <mathlib/math/filter/LowPassFilter2p.hpp>
 #include <lib/conversion/rotation.h>
 #include <platforms/px4_getopt.h>
+#include <systemlib/err.h>
 
 /* SPI protocol address bits */
 #define DIR_READ(a)                     ((a) & 0x7f)
diff --git a/src/drivers/imu/mpu9250/mpu9250.h b/src/drivers/imu/mpu9250/mpu9250.h
index 718729758cca8dd48cd54e11797bc4386f6796aa..2c540aa5b20f71709bb3dd13046d302e12e81d6c 100644
--- a/src/drivers/imu/mpu9250/mpu9250.h
+++ b/src/drivers/imu/mpu9250/mpu9250.h
@@ -48,6 +48,7 @@
 #include <drivers/drv_mag.h>
 #include <mathlib/math/filter/LowPassFilter2p.hpp>
 #include <lib/conversion/rotation.h>
+#include <systemlib/err.h>
 
 #include <uORB/uORB.h>
 #include <uORB/topics/debug_key_value.h>
diff --git a/src/drivers/linux_pwm_out/linux_pwm_out.cpp b/src/drivers/linux_pwm_out/linux_pwm_out.cpp
index 181ab7f3f044985096a9f5a56de591cf1eb276bc..c8112dd9a0a369eb831551efa4377700e3a0e3b4 100644
--- a/src/drivers/linux_pwm_out/linux_pwm_out.cpp
+++ b/src/drivers/linux_pwm_out/linux_pwm_out.cpp
@@ -31,13 +31,16 @@
  *
  ****************************************************************************/
 
+#include <errno.h>
 #include <stdint.h>
+#include <stdlib.h>
+#include <string.h>
+
+#include <cmath>
 
 #include <px4_tasks.h>
 #include <px4_getopt.h>
 #include <px4_posix.h>
-#include <errno.h>
-#include <cmath>	// NAN
 
 #include <uORB/uORB.h>
 #include <uORB/topics/actuator_controls.h>
@@ -461,8 +464,6 @@ void task_main_trampoline(int argc, char *argv[])
 
 void start()
 {
-	ASSERT(_task_handle == -1);
-
 	_task_should_exit = false;
 
 	/* start the task */
@@ -474,7 +475,7 @@ void start()
 					  nullptr);
 
 	if (_task_handle < 0) {
-		warn("task start failed");
+		PX4_ERR("task start failed");
 		return;
 	}
 
diff --git a/src/drivers/linux_sbus/linux_sbus.cpp b/src/drivers/linux_sbus/linux_sbus.cpp
index dc438d4bbdb236f4de10584c4880d620ace141a3..b0758324803ad68bcad70a6283a32d58de6d301c 100644
--- a/src/drivers/linux_sbus/linux_sbus.cpp
+++ b/src/drivers/linux_sbus/linux_sbus.cpp
@@ -33,7 +33,12 @@
  *
  ****************************************************************************/
 #include "linux_sbus.h"
+
+#include <stdlib.h>
+#include <string.h>
+
 using namespace linux_sbus;
+
 //---------------------------------------------------------------------------------------------------------//
 int RcInput::init()
 {
diff --git a/src/drivers/magnetometer/lis3mdl/lis3mdl.h b/src/drivers/magnetometer/lis3mdl/lis3mdl.h
index d27520e034f58f5c968f4150d1363c800ba22e38..febfbb216cf2ee52dc28a7791d8494345c953f09 100644
--- a/src/drivers/magnetometer/lis3mdl/lis3mdl.h
+++ b/src/drivers/magnetometer/lis3mdl/lis3mdl.h
@@ -47,6 +47,7 @@
 #include <drivers/drv_mag.h>
 
 #include <lib/conversion/rotation.h>
+#include <systemlib/err.h>
 
 #include <perf/perf_counter.h>
 #include <px4_defines.h>
diff --git a/src/drivers/magnetometer/lsm303agr/LSM303AGR.hpp b/src/drivers/magnetometer/lsm303agr/LSM303AGR.hpp
index 89e91e8ec2705b874136d3a9ef3e92bb57784af0..3a7d61f5b5b8809cf3d9e36f62476049a89e55f5 100644
--- a/src/drivers/magnetometer/lsm303agr/LSM303AGR.hpp
+++ b/src/drivers/magnetometer/lsm303agr/LSM303AGR.hpp
@@ -43,6 +43,7 @@
 #include <lib/conversion/rotation.h>
 #include <perf/perf_counter.h>
 #include <px4_workqueue.h>
+#include <systemlib/err.h>
 
 // Register mapping
 static constexpr uint8_t WHO_AM_I_M = 0x4F;
diff --git a/src/drivers/magnetometer/rm3100/rm3100.h b/src/drivers/magnetometer/rm3100/rm3100.h
index 23aa3d5d51f695b7411bdbd83660184c536bed84..872fce42970c34c6c11bacded78b0dd9770cf0f1 100644
--- a/src/drivers/magnetometer/rm3100/rm3100.h
+++ b/src/drivers/magnetometer/rm3100/rm3100.h
@@ -50,6 +50,7 @@
 
 #include <perf/perf_counter.h>
 #include <px4_defines.h>
+#include <systemlib/err.h>
 
 #ifndef CONFIG_SCHED_WORKQUEUE
 # error This requires CONFIG_SCHED_WORKQUEUE.
diff --git a/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp b/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp
index 087e609c0eaf0cf9964fa3f4736142811dd61d44..5e38fed10f8d4efa77eba740b59abdc2ae58cda9 100644
--- a/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp
+++ b/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp
@@ -38,7 +38,7 @@
 #include <px4_posix.h>
 #include <errno.h>
 #include <cmath>	// NAN
-
+#include <string.h>
 
 #include <uORB/uORB.h>
 #include <uORB/topics/actuator_controls.h>
@@ -505,8 +505,6 @@ void task_main_trampoline(int argc, char *argv[])
 
 void start()
 {
-	ASSERT(_task_handle == -1);
-
 	_task_should_exit = false;
 
 	/* start the task */
@@ -518,7 +516,7 @@ void start()
 					  nullptr);
 
 	if (_task_handle < 0) {
-		warn("task start failed");
+		PX4_ERR("task start failed");
 		return;
 	}
 
diff --git a/src/drivers/spektrum_rc/spektrum_rc.cpp b/src/drivers/spektrum_rc/spektrum_rc.cpp
index 780c0146af38ceb6be234ac3f3bed65f12325828..c12019e9eff907dad5b4b73f4bcf000647678fd9 100644
--- a/src/drivers/spektrum_rc/spektrum_rc.cpp
+++ b/src/drivers/spektrum_rc/spektrum_rc.cpp
@@ -39,6 +39,8 @@
  * on the serial port. By default port J12 (next to J13, power module side) is used.
  */
 
+#include <string.h>
+
 #include <px4_tasks.h>
 #include <px4_posix.h>
 #include <px4_getopt.h>
@@ -212,8 +214,6 @@ int start(int argc, char *argv[])
 		return -1;
 	}
 
-	ASSERT(_task_handle == -1);
-
 	_task_should_exit = false;
 
 	_task_handle = px4_task_spawn_cmd("spektrum_rc_main",
diff --git a/src/drivers/uavcan/sensors/sensor_bridge.hpp b/src/drivers/uavcan/sensors/sensor_bridge.hpp
index 7138ec337be14348ae15c69585ba4313914f0676..f2bde2295878b64e554686034d1f55758f07f7a3 100644
--- a/src/drivers/uavcan/sensors/sensor_bridge.hpp
+++ b/src/drivers/uavcan/sensors/sensor_bridge.hpp
@@ -41,6 +41,7 @@
 #include <uavcan/uavcan.hpp>
 #include <drivers/device/device.h>
 #include <drivers/drv_orb_dev.h>
+#include <uORB/uORB.h>
 
 /**
  * A sensor bridge class must implement this interface.
diff --git a/src/examples/bottle_drop/bottle_drop.cpp b/src/examples/bottle_drop/bottle_drop.cpp
index eca17abc9ccb18b6ade31dbbfcc60b5d3df1b211..5b32587e44d0a2cca7988c9f34064ca25af49ce2 100644
--- a/src/examples/bottle_drop/bottle_drop.cpp
+++ b/src/examples/bottle_drop/bottle_drop.cpp
@@ -222,8 +222,6 @@ BottleDrop::~BottleDrop()
 int
 BottleDrop::start()
 {
-	ASSERT(_main_task == -1);
-
 	/* start the task */
 	_main_task = px4_task_spawn_cmd("bottle_drop",
 					SCHED_DEFAULT,
diff --git a/src/include/px4.h b/src/include/px4.h
index 34137ee6f4ecb893e027aa2fac9ead0e80da8e2b..fd1f72fba3da2db899a6fff6db1792deb4a41bf1 100644
--- a/src/include/px4.h
+++ b/src/include/px4.h
@@ -39,7 +39,6 @@
 
 #pragma once
 
-#include "../platforms/px4_includes.h"
 #include "../platforms/px4_defines.h"
 #ifdef __cplusplus
 #include "../platforms/px4_middleware.h"
diff --git a/src/lib/cdev/posix/cdev_platform.hpp b/src/lib/cdev/posix/cdev_platform.hpp
index 92edf1262578b2c50a1e86956c4309d5dc1443bc..c78d21c7a7ceb48eec1164268ffea59d67b86827 100644
--- a/src/lib/cdev/posix/cdev_platform.hpp
+++ b/src/lib/cdev/posix/cdev_platform.hpp
@@ -2,6 +2,7 @@
 #pragma once
 
 #include <inttypes.h>
+#include <string.h>
 
 #define ATOMIC_ENTER lock()
 #define ATOMIC_LEAVE unlock()
diff --git a/src/lib/drivers/linux_gpio/linux_gpio.cpp b/src/lib/drivers/linux_gpio/linux_gpio.cpp
index dfc6a3be765110449178aa05bf95d3b1c891f23c..79b7129c2fecb3c57862b11aeaa853ed58dcbf76 100644
--- a/src/lib/drivers/linux_gpio/linux_gpio.cpp
+++ b/src/lib/drivers/linux_gpio/linux_gpio.cpp
@@ -33,10 +33,14 @@
 
 #include "linux_gpio.h"
 
-#include <px4_posix.h>
 #include <sys/types.h>
 #include <sys/stat.h>
 #include <fcntl.h>
+#include <errno.h>
+#include <string.h>
+#include <stdlib.h>
+
+#include <px4_posix.h>
 
 #define PIN_INDEX_BUFFER_MAX (16)
 #define PIN_DIRECTION_BUFFER_MAX (30 + PIN_INDEX_BUFFER_MAX)
diff --git a/src/lib/parameters/flashparams/flashparams.cpp b/src/lib/parameters/flashparams/flashparams.cpp
index 5e5e61d373d35ebc581b10eae7be765e8698305f..db2fdb17cee23b387dac4cee91494f6db8d26002 100644
--- a/src/lib/parameters/flashparams/flashparams.cpp
+++ b/src/lib/parameters/flashparams/flashparams.cpp
@@ -45,9 +45,11 @@
 #include <px4_defines.h>
 #include <px4_posix.h>
 #include <px4_shutdown.h>
+
 #include <string.h>
 #include <stdbool.h>
 #include <stdint.h>
+#include <errno.h>
 
 #include <parameters/param.h>
 
diff --git a/src/lib/tunes/tunes.cpp b/src/lib/tunes/tunes.cpp
index c3b73f91d6b4363b4813b1930cd7b4cc9e087c9e..b1dcc44dcf90d712444a3fe4646318430938ddb1 100644
--- a/src/lib/tunes/tunes.cpp
+++ b/src/lib/tunes/tunes.cpp
@@ -40,6 +40,7 @@
 #include <px4_log.h>
 #include <math.h>
 #include <ctype.h>
+#include <errno.h>
 
 #define TUNE_ERROR -1
 #define TUNE_STOP 0
diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp
index d18c995c88748d8f11242b7df575f7ec0f0db87c..9183d6f21e32ca475b53ca74b0a53104adb3e470 100644
--- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp
+++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp
@@ -229,8 +229,6 @@ AttitudeEstimatorQ::~AttitudeEstimatorQ()
 
 int AttitudeEstimatorQ::start()
 {
-	ASSERT(_control_task == -1);
-
 	/* start the task */
 	_control_task = px4_task_spawn_cmd("attitude_estimator_q",
 					   SCHED_DEFAULT,
diff --git a/src/modules/gnd_att_control/GroundRoverAttitudeControl.cpp b/src/modules/gnd_att_control/GroundRoverAttitudeControl.cpp
index 3288ed81949b2a993d924af433209d09f2f8f1b4..95d1b8e5554fbc25bdeab60bb56f5f5c70d31450 100644
--- a/src/modules/gnd_att_control/GroundRoverAttitudeControl.cpp
+++ b/src/modules/gnd_att_control/GroundRoverAttitudeControl.cpp
@@ -223,7 +223,7 @@ GroundRoverAttitudeControl::task_main()
 
 		/* this is undesirable but not much we can do - might want to flag unhappy status */
 		if (pret < 0) {
-			warn("poll error %d, %d", pret, errno);
+			PX4_ERR("poll error %d, %d", pret, errno);
 			continue;
 		}
 
@@ -298,7 +298,7 @@ GroundRoverAttitudeControl::task_main()
 						perf_count(_nonfinite_output_perf);
 
 						if (_debug && loop_counter % 10 == 0) {
-							warnx("yaw_u %.4f", (double)yaw_u);
+							PX4_INFO("yaw_u %.4f", (double)yaw_u);
 						}
 					}
 
@@ -343,7 +343,7 @@ GroundRoverAttitudeControl::task_main()
 		perf_end(_loop_perf);
 	}
 
-	warnx("exiting.\n");
+	PX4_INFO("exiting.");
 
 	_control_task = -1;
 	_task_running = false;
@@ -352,8 +352,6 @@ GroundRoverAttitudeControl::task_main()
 int
 GroundRoverAttitudeControl::start()
 {
-	ASSERT(_control_task == -1);
-
 	/* start the task */
 	_control_task = px4_task_spawn_cmd("gnd_att_control",
 					   SCHED_DEFAULT,
@@ -363,7 +361,7 @@ GroundRoverAttitudeControl::start()
 					   nullptr);
 
 	if (_control_task < 0) {
-		warn("task start failed");
+		PX4_ERR("task start failed");
 		return -errno;
 	}
 
@@ -373,28 +371,28 @@ GroundRoverAttitudeControl::start()
 int gnd_att_control_main(int argc, char *argv[])
 {
 	if (argc < 2) {
-		warnx("usage: gnd_att_control {start|stop|status}");
+		PX4_INFO("usage: gnd_att_control {start|stop|status}");
 		return 1;
 	}
 
 	if (!strcmp(argv[1], "start")) {
 
 		if (att_gnd_control::g_control != nullptr) {
-			warnx("already running");
+			PX4_WARN("already running");
 			return 1;
 		}
 
 		att_gnd_control::g_control = new GroundRoverAttitudeControl;
 
 		if (att_gnd_control::g_control == nullptr) {
-			warnx("alloc failed");
+			PX4_ERR("alloc failed");
 			return 1;
 		}
 
 		if (PX4_OK != att_gnd_control::g_control->start()) {
 			delete att_gnd_control::g_control;
 			att_gnd_control::g_control = nullptr;
-			warn("start failed");
+			PX4_ERR("start failed");
 			return 1;
 		}
 
@@ -416,7 +414,7 @@ int gnd_att_control_main(int argc, char *argv[])
 
 	if (!strcmp(argv[1], "stop")) {
 		if (att_gnd_control::g_control == nullptr) {
-			warnx("not running");
+			PX4_WARN("not running");
 			return 1;
 		}
 
@@ -427,15 +425,15 @@ int gnd_att_control_main(int argc, char *argv[])
 
 	if (!strcmp(argv[1], "status")) {
 		if (att_gnd_control::g_control) {
-			warnx("running");
+			PX4_INFO("running");
 			return 0;
 
 		} else {
-			warnx("not running");
+			PX4_INFO("not running");
 			return 1;
 		}
 	}
 
-	warnx("unrecognized command");
+	PX4_WARN("unrecognized command");
 	return 1;
 }
diff --git a/src/modules/gnd_pos_control/GroundRoverPositionControl.cpp b/src/modules/gnd_pos_control/GroundRoverPositionControl.cpp
index e3013956caace05b9cfe2e5afffcab3ddc041ec5..10cf8e40af78dce2473192e1a4c706c34b30bacc 100644
--- a/src/modules/gnd_pos_control/GroundRoverPositionControl.cpp
+++ b/src/modules/gnd_pos_control/GroundRoverPositionControl.cpp
@@ -484,8 +484,6 @@ GroundRoverPositionControl::task_main_trampoline(int argc, char *argv[])
 int
 GroundRoverPositionControl::start()
 {
-	ASSERT(_control_task == -1);
-
 	/* start the task */
 	_control_task = px4_task_spawn_cmd("gnd_pos_ctrl",
 					   SCHED_DEFAULT,
diff --git a/src/modules/logger/log_writer_file.cpp b/src/modules/logger/log_writer_file.cpp
index 435f8c165226eb4fa16a7fcee14d4d6619418d4d..c47cf5cda254e6169fb45920bec5253b9ae0f7a1 100644
--- a/src/modules/logger/log_writer_file.cpp
+++ b/src/modules/logger/log_writer_file.cpp
@@ -33,8 +33,10 @@
 
 #include "log_writer_file.h"
 #include "messages.h"
+
 #include <fcntl.h>
 #include <string.h>
+#include <errno.h>
 
 #include <mathlib/mathlib.h>
 #include <px4_posix.h>
diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp
index 5b071aac43f4fe378ada8d72656380edd4e6af17..ae7a2b0040c2d28912cb7cb5c333cf87e2106fd6 100644
--- a/src/modules/logger/logger.cpp
+++ b/src/modules/logger/logger.cpp
@@ -52,7 +52,6 @@
 #include <uORB/topics/vehicle_command_ack.h>
 
 #include <drivers/drv_hrt.h>
-#include <px4_includes.h>
 #include <px4_getopt.h>
 #include <px4_log.h>
 #include <px4_posix.h>
diff --git a/src/modules/mavlink/mavlink_timesync.cpp b/src/modules/mavlink/mavlink_timesync.cpp
index 41c23a3068edfda08a64f36ac1a74f44526ac8e9..abd12f621f07d72229bdb49fa94c8ed16568143d 100644
--- a/src/modules/mavlink/mavlink_timesync.cpp
+++ b/src/modules/mavlink/mavlink_timesync.cpp
@@ -41,6 +41,8 @@
 #include "mavlink_timesync.h"
 #include "mavlink_main.h"
 
+#include <stdlib.h>
+
 MavlinkTimesync::MavlinkTimesync(Mavlink *mavlink) :
 	_mavlink(mavlink)
 {
diff --git a/src/modules/muorb/adsp/uORBFastRpcChannel.cpp b/src/modules/muorb/adsp/uORBFastRpcChannel.cpp
index c91c7f2e204af72fc1537d3622580ca24c4d62f6..e7c0cc2494dae5bf423376702bdc55dac8a025a6 100644
--- a/src/modules/muorb/adsp/uORBFastRpcChannel.cpp
+++ b/src/modules/muorb/adsp/uORBFastRpcChannel.cpp
@@ -33,6 +33,7 @@
 #include "uORBFastRpcChannel.hpp"
 #include "px4_log.h"
 #include <algorithm>
+#include <string.h>
 #include <drivers/drv_hrt.h>
 
 // static initialization.
diff --git a/src/modules/muorb/krait/px4muorb_KraitRpcWrapper.cpp b/src/modules/muorb/krait/px4muorb_KraitRpcWrapper.cpp
index d697a973737a68eac5fce5f86947ed6b3f2891d2..f4a70e8e7d321d08e7b5cc4d79aca8737a42695d 100644
--- a/src/modules/muorb/krait/px4muorb_KraitRpcWrapper.cpp
+++ b/src/modules/muorb/krait/px4muorb_KraitRpcWrapper.cpp
@@ -40,6 +40,7 @@
 #include "px4_log.h"
 #include <shmem.h>
 #include <drivers/drv_hrt.h>
+#include <string.h>
 
 using namespace px4muorb;
 
diff --git a/src/modules/muorb/krait/uORBKraitFastRpcChannel.cpp b/src/modules/muorb/krait/uORBKraitFastRpcChannel.cpp
index a441522d42128bdb59b9e2ddcac47f4b259ba65d..dae0d0260e978b7390960194a4d7b41339dcf10f 100644
--- a/src/modules/muorb/krait/uORBKraitFastRpcChannel.cpp
+++ b/src/modules/muorb/krait/uORBKraitFastRpcChannel.cpp
@@ -37,6 +37,7 @@
 #include <drivers/drv_hrt.h>
 #include <cstdio>
 #include <pthread.h>
+#include <string.h>
 
 #define LOG_TAG "uORBKraitFastRpcChannel.cpp"
 
diff --git a/src/platforms/common/px4_log.c b/src/platforms/common/px4_log.c
index 850710121ab0966daa279a689bdb274a928a8c85..ab58acdfbbc3cf622a298850fe7fd579786877f6 100644
--- a/src/platforms/common/px4_log.c
+++ b/src/platforms/common/px4_log.c
@@ -31,9 +31,11 @@
  *
  ****************************************************************************/
 
+#include <assert.h>
 #include <stdio.h>
 #include <stdlib.h>
 #include <string.h>
+
 #include <px4_log.h>
 #if defined(__PX4_POSIX)
 #if !defined(__PX4_CYGWIN)
@@ -55,7 +57,7 @@ __EXPORT const char *__px4_log_level_color[_PX4_LOG_LEVEL_PANIC + 1] =
 
 void px4_log_initialize(void)
 {
-	ASSERT(orb_log_message_pub == NULL);
+	assert(orb_log_message_pub == NULL);
 
 	/* we need to advertise with a valid message */
 	struct log_message_s log_message;
diff --git a/src/platforms/common/work_queue/hrt_thread.c b/src/platforms/common/work_queue/hrt_thread.c
index df1f0bd75eb734dbe917144aa195744348b04047..d1a94f96da0e597a2f4af27afb70484ed47e0500 100644
--- a/src/platforms/common/work_queue/hrt_thread.c
+++ b/src/platforms/common/work_queue/hrt_thread.c
@@ -52,6 +52,8 @@
 #include <drivers/drv_hrt.h>
 #include "hrt_work.h"
 
+#include <string.h>
+
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
diff --git a/src/platforms/posix/drivers/df_bebop_bus_wrapper/df_bebop_bus_wrapper.cpp b/src/platforms/posix/drivers/df_bebop_bus_wrapper/df_bebop_bus_wrapper.cpp
index 4daac7de244220e1fa7e822b136da7c1b90add94..868ce3c81898ce9a670d95b2c6ebb508187c6285 100644
--- a/src/platforms/posix/drivers/df_bebop_bus_wrapper/df_bebop_bus_wrapper.cpp
+++ b/src/platforms/posix/drivers/df_bebop_bus_wrapper/df_bebop_bus_wrapper.cpp
@@ -39,6 +39,7 @@
  * motor and contol commands to the Bebop and reads its status and informations.
  */
 
+#include <stdlib.h>
 #include <stdint.h>
 
 #include <px4_tasks.h>
@@ -300,7 +301,7 @@ int initialize_mixers(const char *mixers_filename)
 	PX4_INFO("Trying to initialize mixers from config file %s", mixers_filename);
 
 	if (load_mixer_file(mixers_filename, &buf[0], sizeof(buf)) < 0) {
-		warnx("can't load mixer: %s", mixers_filename);
+		PX4_ERR("can't load mixer: %s", mixers_filename);
 		return -1;
 	}
 
@@ -484,9 +485,6 @@ int start()
 	DevMgr::releaseHandle(h);
 
 	// Start the task to forward the motor control commands
-	ASSERT(_task_handle == -1);
-
-	/* start the task */
 	_task_handle = px4_task_spawn_cmd("bebop_bus_esc_main",
 					  SCHED_DEFAULT,
 					  SCHED_PRIORITY_MAX,
@@ -495,7 +493,7 @@ int start()
 					  nullptr);
 
 	if (_task_handle < 0) {
-		warn("task start failed");
+		PX4_ERR("task start failed");
 		return -1;
 	}
 
diff --git a/src/platforms/px4_defines.h b/src/platforms/px4_defines.h
index a75eaca6ce40abdbe5e24c50d9d233af0ca8b245..28a25350dea9928f903a366c6a54d2bd7812b3e2 100644
--- a/src/platforms/px4_defines.h
+++ b/src/platforms/px4_defines.h
@@ -77,7 +77,6 @@
  * Building for NuttX or POSIX.
  ****************************************************************************/
 
-#include <platforms/px4_includes.h>
 /* Main entry point */
 #define PX4_MAIN_FUNCTION(_prefix) int _prefix##_task_main(int argc, char *argv[])
 
diff --git a/src/platforms/px4_includes.h b/src/platforms/px4_includes.h
deleted file mode 100644
index 38d5e455a4f22322ff42e7c25a2fd2047eb0bb7b..0000000000000000000000000000000000000000
--- a/src/platforms/px4_includes.h
+++ /dev/null
@@ -1,80 +0,0 @@
-/****************************************************************************
- *
- *   Copyright (c) 2014 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- *    notice, this list of conditions and the following disclaimer in
- *    the documentation and/or other materials provided with the
- *    distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- *    used to endorse or promote products derived from this software
- *    without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file px4_includes.h
- *
- * Includes headers depending on the build target
- */
-
-#pragma once
-
-#if defined(__PX4_NUTTX)
-/*
- * Building for NuttX
- */
-#include <nuttx/config.h>
-#include <uORB/uORB.h>
-
-#include <systemlib/err.h>
-#include <parameters/param.h>
-
-#elif defined(__PX4_POSIX) && !defined(__PX4_QURT)
-/*
- * Building for Posix
- */
-#include <string.h>
-#include <assert.h>
-#include <uORB/uORB.h>
-
-#define ASSERT(x) assert(x)
-
-#include <systemlib/err.h>
-#include <parameters/param.h>
-
-#elif defined(__PX4_QURT)
-/*
- * Building for QuRT
- */
-#include <string.h>
-#include <assert.h>
-#include <uORB/uORB.h>
-
-#define ASSERT(x) assert(x)
-
-#include <systemlib/err.h>
-#include <parameters/param.h>
-
-#else
-#error "No target platform defined"
-#endif
diff --git a/src/platforms/px4_log.h b/src/platforms/px4_log.h
index b91e957c5307c37d86f34342befd69dceca7501f..b0f394ee5264254669784d6490899d8e08c2fb57 100644
--- a/src/platforms/px4_log.h
+++ b/src/platforms/px4_log.h
@@ -38,7 +38,6 @@
 
 #pragma once
 
-
 #define _PX4_LOG_LEVEL_DEBUG		0
 #define _PX4_LOG_LEVEL_INFO		1
 #define _PX4_LOG_LEVEL_WARN		2
diff --git a/src/systemcmds/led_control/led_control.cpp b/src/systemcmds/led_control/led_control.cpp
index 94f4e274ed30ff0b16822baa96216b8253a78dcf..fa502fa5463523206d437b632ac1dc5afce86b83 100644
--- a/src/systemcmds/led_control/led_control.cpp
+++ b/src/systemcmds/led_control/led_control.cpp
@@ -39,6 +39,7 @@
 #include <px4_module.h>
 #include <px4_log.h>
 
+#include <stdlib.h>
 #include <unistd.h>
 
 #include <drivers/drv_hrt.h>
diff --git a/src/systemcmds/sd_bench/sd_bench.c b/src/systemcmds/sd_bench/sd_bench.c
index 260225ccb4d0e54aa2d671b60d4dfb8bbe17e6b5..b931f86decacc44ba0c4f1185d1197ad0782e655 100644
--- a/src/systemcmds/sd_bench/sd_bench.c
+++ b/src/systemcmds/sd_bench/sd_bench.c
@@ -44,7 +44,6 @@
 
 #include <px4_config.h>
 #include <px4_module.h>
-#include <px4_includes.h>
 #include <px4_getopt.h>
 #include <px4_log.h>
 
diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp
index 714a91d6d98673ddd7d03464043ef6c7eb400528..7d0d3bd3e9e50a24fdf26b27a8e9a7e19721ae16 100644
--- a/src/systemcmds/tests/test_mixer.cpp
+++ b/src/systemcmds/tests/test_mixer.cpp
@@ -38,8 +38,10 @@
  */
 
 #include <dirent.h>
+#include <stdlib.h>
 #include <string.h>
 #include <unistd.h>
+#include <math.h>
 
 #include <px4_config.h>
 #include <mixer/mixer.h>
@@ -397,13 +399,13 @@ bool MixerTest::mixerTest()
 
 		if (i != actuator_controls_s::INDEX_THROTTLE) {
 			if (r_page_servos[i] < r_page_servo_control_min[i]) {
-				warnx("active servo < min");
+				PX4_ERR("active servo < min");
 				return false;
 			}
 
 		} else {
 			if (r_page_servos[i] != r_page_servo_disarmed[i]) {
-				warnx("throttle output != 0 (this check assumed the IO pass mixer!)");
+				PX4_ERR("throttle output != 0 (this check assumed the IO pass mixer!)");
 				return false;
 			}
 		}
diff --git a/src/systemcmds/tests/test_parameters.cpp b/src/systemcmds/tests/test_parameters.cpp
index 317309fc8d67bf9e9517b0b0fa2ff160420beb49..45cefe5414356948abfcb16d5fa24f96f3c2f3ce 100644
--- a/src/systemcmds/tests/test_parameters.cpp
+++ b/src/systemcmds/tests/test_parameters.cpp
@@ -1,6 +1,8 @@
 #include <unit_test.h>
 
 #include <px4_defines.h>
+
+#include <errno.h>
 #include <fcntl.h>
 #include <unistd.h>
 
diff --git a/src/systemcmds/tune_control/tune_control.cpp b/src/systemcmds/tune_control/tune_control.cpp
index cd1a69a176632234f5a4ba029c31d1667304cf61..b47dc61d7a395095cb66cf2576dd7e421d5003ff 100644
--- a/src/systemcmds/tune_control/tune_control.cpp
+++ b/src/systemcmds/tune_control/tune_control.cpp
@@ -41,8 +41,10 @@
 #include <px4_getopt.h>
 #include <px4_log.h>
 
+#include <stdlib.h>
 #include <string.h>
 #include <unistd.h>
+#include <errno.h>
 
 #include <px4_module.h>