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

This commit is contained in:
Beat Küng 2022-07-19 15:27:10 +02:00 committed by Daniel Agar
parent ea136e73be
commit f22dc80ecc
15 changed files with 22 additions and 2 deletions

View File

@ -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)

View File

@ -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>

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -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;

View File

@ -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"

View File

@ -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>

View File

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

View File

@ -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();