Browse Source

system: add missing includes (added indirectly via visibility.h for normal builds)

main
Beat Küng 3 years ago committed by Daniel Agar
parent
commit
f22dc80ecc
  1. 1
      boards/px4/sitl/src/board_shutdown.cpp
  2. 4
      platforms/nuttx/src/px4/common/board_crashdump.c
  3. 2
      platforms/nuttx/src/px4/common/cdc_acm_check.cpp
  4. 2
      platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/spi_hw_description.h
  5. 1
      platforms/posix/src/px4/common/lockstep_scheduler/include/lockstep_scheduler/lockstep_scheduler.h
  6. 1
      src/drivers/imu/invensense/icm20602/InvenSense_ICM20602_registers.hpp
  7. 1
      src/drivers/imu/invensense/icm20689/InvenSense_ICM20689_registers.hpp
  8. 1
      src/drivers/imu/invensense/icm20948/InvenSense_ICM20948_registers.hpp
  9. 1
      src/drivers/imu/invensense/icm42688p/InvenSense_ICM42688P_registers.hpp
  10. 1
      src/include/containers/Bitset.hpp
  11. 2
      src/lib/cdev/posix/cdev_platform.cpp
  12. 1
      src/modules/dataman/dataman.cpp
  13. 2
      src/systemcmds/gpio/gpio.cpp
  14. 2
      src/systemcmds/i2cdetect/i2cdetect.cpp
  15. 2
      src/systemcmds/system_time/system_time.cpp

1
boards/px4/sitl/src/board_shutdown.cpp

@ -40,6 +40,7 @@ @@ -40,6 +40,7 @@
#include <px4_platform_common/tasks.h>
#include <board_config.h>
#include <stdio.h>
#include <stdlib.h>
#if defined(BOARD_HAS_POWER_CONTROL)
int board_register_power_state_notification_cb(power_button_state_notification_t cb)

4
platforms/nuttx/src/px4/common/board_crashdump.c

@ -38,10 +38,10 @@ @@ -38,10 +38,10 @@
* and hardfault log support
*/
#ifdef CONFIG_BOARD_CRASHDUMP
#include <board_config.h>
#ifdef CONFIG_BOARD_CRASHDUMP
#include <stdio.h>
#include <stdbool.h>
#include <string.h>

2
platforms/nuttx/src/px4/common/cdc_acm_check.cpp

@ -31,6 +31,8 @@ @@ -31,6 +31,8 @@
*
****************************************************************************/
#include <board_config.h>
#if defined(CONFIG_SYSTEM_CDCACM)
__BEGIN_DECLS
#include <arch/board/board.h>

2
platforms/nuttx/src/px4/stm/stm32f7/include/px4_arch/spi_hw_description.h

@ -32,6 +32,8 @@ @@ -32,6 +32,8 @@
****************************************************************************/
#pragma once
#include <board_config.h>
#if defined(CONFIG_SPI)
#include "../../../stm32_common/include/px4_arch/spi_hw_description.h"

1
platforms/posix/src/px4/common/lockstep_scheduler/include/lockstep_scheduler/lockstep_scheduler.h

@ -39,6 +39,7 @@ @@ -39,6 +39,7 @@
#include <memory>
#include <atomic>
#include <pthread.h>
#include <unistd.h>
#include "lockstep_components.h"

1
src/drivers/imu/invensense/icm20602/InvenSense_ICM20602_registers.hpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
#pragma once
#include <cstdint>
#include <cstddef>
// TODO: move to a central header
static constexpr uint8_t Bit0 = (1 << 0);

1
src/drivers/imu/invensense/icm20689/InvenSense_ICM20689_registers.hpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
#pragma once
#include <cstdint>
#include <cstddef>
// TODO: move to a central header
static constexpr uint8_t Bit0 = (1 << 0);

1
src/drivers/imu/invensense/icm20948/InvenSense_ICM20948_registers.hpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
#pragma once
#include <cstdint>
#include <cstddef>
namespace InvenSense_ICM20948
{

1
src/drivers/imu/invensense/icm42688p/InvenSense_ICM42688P_registers.hpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
#pragma once
#include <cstdint>
#include <cstddef>
namespace InvenSense_ICM42688P
{

1
src/include/containers/Bitset.hpp

@ -34,6 +34,7 @@ @@ -34,6 +34,7 @@
#pragma once
#include <stdint.h>
#include <stddef.h>
namespace px4
{

2
src/lib/cdev/posix/cdev_platform.cpp

@ -40,6 +40,8 @@ @@ -40,6 +40,8 @@
#include <px4_platform_common/posix.h>
#include <px4_platform_common/time.h>
#include <stdlib.h>
const cdev::px4_file_operations_t cdev::CDev::fops = {};
pthread_mutex_t devmutex = PTHREAD_MUTEX_INITIALIZER;

1
src/modules/dataman/dataman.cpp

@ -50,6 +50,7 @@ @@ -50,6 +50,7 @@
#include <drivers/drv_hrt.h>
#include <lib/parameters/param.h>
#include <lib/perf/perf_counter.h>
#include <stdlib.h>
#include "dataman.h"

2
src/systemcmds/gpio/gpio.cpp

@ -42,6 +42,8 @@ @@ -42,6 +42,8 @@
#include <px4_platform_common/module.h>
#include <px4_platform_common/px4_config.h>
#include <stdlib.h>
#include <nuttx/ioexpander/gpio.h>
#include <fcntl.h>

2
src/systemcmds/i2cdetect/i2cdetect.cpp

@ -43,6 +43,8 @@ @@ -43,6 +43,8 @@
#include <px4_platform_common/module.h>
#include <px4_platform_common/getopt.h>
#include <stdlib.h>
namespace i2cdetect
{

2
src/systemcmds/system_time/system_time.cpp

@ -34,6 +34,8 @@ @@ -34,6 +34,8 @@
#include <px4_platform_common/module.h>
#include <px4_platform_common/time.h>
#include <stdlib.h>
using namespace time_literals;
static void usage();

Loading…
Cancel
Save