mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
delete px4_includes.h header and update boards/ to use syslog
This commit is contained in:
parent
376e078c24
commit
2ffb49b734
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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 */
|
||||
//
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
@ -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 */
|
||||
|
||||
|
||||
@ -57,7 +57,6 @@
|
||||
#include <chip.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include "board_config.h"
|
||||
#include <systemlib/err.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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);
|
||||
|
||||
@ -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"
|
||||
|
||||
@ -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"
|
||||
|
||||
@ -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>
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
@ -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);
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
@ -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 */
|
||||
|
||||
@ -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 */
|
||||
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
@ -55,7 +55,6 @@
|
||||
#include <chip.h>
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
#include <systemlib/err.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
|
||||
@ -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>
|
||||
|
||||
@ -40,6 +40,8 @@
|
||||
|
||||
#include "video_device.h"
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <sys/stat.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <sys/mman.h>
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
@ -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
|
||||
*
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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 */
|
||||
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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 */
|
||||
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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 */
|
||||
|
||||
|
||||
@ -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 */
|
||||
|
||||
|
||||
@ -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 */
|
||||
|
||||
|
||||
@ -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
|
||||
****************************************************************************/
|
||||
|
||||
@ -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
|
||||
****************************************************************************/
|
||||
|
||||
@ -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 */
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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 */
|
||||
|
||||
|
||||
@ -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>
|
||||
|
||||
@ -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));
|
||||
|
||||
@ -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>
|
||||
|
||||
|
||||
@ -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 = {};
|
||||
|
||||
@ -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[]);
|
||||
|
||||
|
||||
@ -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[]);
|
||||
|
||||
|
||||
@ -36,6 +36,7 @@
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_defines.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <termios.h>
|
||||
|
||||
|
||||
@ -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);
|
||||
}
|
||||
|
||||
@ -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,
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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))
|
||||
|
||||
@ -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)
|
||||
|
||||
@ -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>
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -33,7 +33,12 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
#include "linux_sbus.h"
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
using namespace linux_sbus;
|
||||
|
||||
//---------------------------------------------------------------------------------------------------------//
|
||||
int RcInput::init()
|
||||
{
|
||||
|
||||
@ -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>
|
||||
|
||||
@ -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;
|
||||
|
||||
@ -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.
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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",
|
||||
|
||||
@ -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.
|
||||
|
||||
@ -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,
|
||||
|
||||
@ -39,7 +39,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "../platforms/px4_includes.h"
|
||||
#include "../platforms/px4_defines.h"
|
||||
#ifdef __cplusplus
|
||||
#include "../platforms/px4_middleware.h"
|
||||
|
||||
@ -2,6 +2,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <string.h>
|
||||
|
||||
#define ATOMIC_ENTER lock()
|
||||
#define ATOMIC_LEAVE unlock()
|
||||
|
||||
@ -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)
|
||||
|
||||
@ -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>
|
||||
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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,
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
@ -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,
|
||||
|
||||
@ -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>
|
||||
|
||||
@ -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>
|
||||
|
||||
@ -41,6 +41,8 @@
|
||||
#include "mavlink_timesync.h"
|
||||
#include "mavlink_main.h"
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
MavlinkTimesync::MavlinkTimesync(Mavlink *mavlink) :
|
||||
_mavlink(mavlink)
|
||||
{
|
||||
|
||||
@ -33,6 +33,7 @@
|
||||
#include "uORBFastRpcChannel.hpp"
|
||||
#include "px4_log.h"
|
||||
#include <algorithm>
|
||||
#include <string.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
// static initialization.
|
||||
|
||||
@ -40,6 +40,7 @@
|
||||
#include "px4_log.h"
|
||||
#include <shmem.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <string.h>
|
||||
|
||||
using namespace px4muorb;
|
||||
|
||||
|
||||
@ -37,6 +37,7 @@
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <cstdio>
|
||||
#include <pthread.h>
|
||||
#include <string.h>
|
||||
|
||||
#define LOG_TAG "uORBKraitFastRpcChannel.cpp"
|
||||
|
||||
|
||||
@ -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;
|
||||
|
||||
@ -52,6 +52,8 @@
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include "hrt_work.h"
|
||||
|
||||
#include <string.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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[])
|
||||
|
||||
|
||||
@ -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
|
||||
@ -38,7 +38,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
|
||||
#define _PX4_LOG_LEVEL_DEBUG 0
|
||||
#define _PX4_LOG_LEVEL_INFO 1
|
||||
#define _PX4_LOG_LEVEL_WARN 2
|
||||
|
||||
@ -39,6 +39,7 @@
|
||||
#include <px4_module.h>
|
||||
#include <px4_log.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
@ -44,7 +44,6 @@
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_module.h>
|
||||
#include <px4_includes.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_log.h>
|
||||
|
||||
|
||||
@ -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;
|
||||
}
|
||||
}
|
||||
|
||||
@ -1,6 +1,8 @@
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <px4_defines.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
||||
|
||||
@ -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>
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user