forked from Archive/PX4-Autopilot
Use px4_config.h instead of nuttx/config.h
Modified code to use OS independent header file for config settings. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
82a7fd5115
commit
9758112e31
|
@ -38,7 +38,7 @@
|
|||
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* Generic driver for airspeed sensors connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* Implementation of AR.Drone 1.0 / 2.0 motor control interface.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* Implementation of AR.Drone 1.0 / 2.0 motor control interface
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* @author Randy Mackay <rmackay9@yahoo.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -93,7 +93,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
* Driver for the Bosch BMA 180 MEMS accelerometer connected via SPI.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* AeroCore LED backend.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* PX4FMU LED backend.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* PX4FMU LED backend.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
* Included Files
|
||||
******************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
/*
|
||||
* Includes here should only cover the needs of the framework definitions.
|
||||
*/
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* and output via the standardized control group #2 and a mixer.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
|
|
@ -48,7 +48,7 @@
|
|||
* driver. Use instead the normal FMU or IO driver.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* Driver for the HMC5883 / HMC5983 magnetometer connected via I2C or SPI.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
*/
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <poll.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
*/
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <poll.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* also supported by this driver.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* LED driver.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/drv_led.h>
|
||||
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* Driver for the PulsedLight Lidar-Lite range finders connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
* Driver for the ST LSM303D MEMS accelerometer / magnetometer connected via SPI.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* Driver for the Maxbotix sonar range finders connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
*/
|
||||
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* @author Marco Bauer <marco@wtns.de>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/**
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* @author Pat Hickey
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
* Driver for the MS5611 barometric pressure sensor connected via I2C or SPI.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* which in turn was based on drv_hrt.c
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* Driver for the PX4FLOW module connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* Driver/configurator for the PX4 FMU multi-purpose port on v1 and v2 boards.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* PX4IO is connected via I2C or DMA enabled high-speed UART.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
* Firmware uploader for PX4IO
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdlib.h>
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* Driver for the Lightware SF0x laser rangefinder series
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* and so forth. It avoids the gross complexity of the NuttX ADC driver.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <board_config.h>
|
||||
#include <drivers/device/device.h>
|
||||
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
* claim the timer and then drive it directly.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* have output pins, does not require an interrupt.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
|
|
|
@ -86,7 +86,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <drivers/device/device.h>
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* Driver for the TeraRanger One range finders connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* Optical flow position estimator
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include <string.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/sched.h>
|
||||
|
||||
#include <systemlib/systemlib.h>
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* Debug application example for PX4 autopilot
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
* Minimal application example for PX4 autopilot
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
*/
|
||||
|
||||
#include <geo/geo.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <pthread.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
|
|
|
@ -267,7 +267,7 @@
|
|||
#define __CMSIS_GENERIC /* disable NVIC and Systick functions */
|
||||
|
||||
/* PX4 */
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#ifdef CONFIG_ARCH_CORTEXM4
|
||||
# define ARM_MATH_CM4 1
|
||||
#endif
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -50,7 +50,7 @@
|
|||
* [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* @author Dominik Juchli <juchlid@ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/**
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <pthread.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
* @author Julian Oes <julian@oes.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* @author Thomas Gubler
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <fcntl.h>
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include "AttitudePositionEstimatorEKF.h"
|
||||
#include "estimator_22states.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* Fixedwing backside controller using control library
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -41,7 +41,7 @@ f * Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/*
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
|
||||
#include "landingslope.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <math.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/*
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <pthread.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -53,7 +53,7 @@
|
|||
* If rotation matrix setpoint is invalid it will be generated from Euler angles for compatibility with old position controllers.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue