mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-04 13:15:08 +08:00
Do not include headers inside __BEGIN_DECLS ... __END_DECLS blocks.
We don't have C++ unsafe headers (anymore). I added a test to fix_headers.sh that checks if certain "unsafe" headers are ONLY included inside a __BEGIN_DECLS ... __END_DECLS (because after all, they are unsafe), as well as checking that no other header files are included inside such a block. The rationale of the latter is that if a file is a C header and it declares function prototypes (otherwise it doesn't matter) and is sometimes included outside a __BEGIN_DECLS ... __END_DECLS block (from a C++ source file) then it has to be C++ safe and doesn't ever to be included from inside such a block; while if a file is a C++ header then obviously it should never be included from such a block. fix_headers.sh subsequently found several safe headers to be included from inside such a block, and those that were (apparently in the past) unsafe were included only sometimes inside such a block and often outside it. I had a look at those files and saw that at least an attempt has been made to make them C++ safe, but especially because they already are included OFTEN outside a __BEGIN_DECLS ... __END_DECLS (from C++ source files) the best decision seems to treat them as safe. This is not risky: .c files that define such functions still generate C-linkage for their functions. If a C++ unsafe C header is included outside a __BEGIN_DECLS ... __END_DECLS block then the only possible result would be an undefined reference to a function with C++-linkage that will not exist. Aka, when something links after this commit, then the commit was correct. I did build all targets and they all linked.
This commit is contained in:
@@ -47,9 +47,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -189,6 +186,8 @@ __BEGIN_DECLS
|
|||||||
{GPIO_GPIO10_INPUT, GPIO_GPIO10_OUTPUT, 0}, \
|
{GPIO_GPIO10_INPUT, GPIO_GPIO10_OUTPUT, 0}, \
|
||||||
{GPIO_GPIO11_INPUT, GPIO_GPIO11_OUTPUT, 0}, }
|
{GPIO_GPIO11_INPUT, GPIO_GPIO11_OUTPUT, 0}, }
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
* Public Types
|
* Public Types
|
||||||
****************************************************************************************************/
|
****************************************************************************************************/
|
||||||
|
|||||||
@@ -50,9 +50,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -259,6 +256,9 @@ __BEGIN_DECLS
|
|||||||
#define TEMP_CONTROL(_on_true) px4_arch_gpiowrite(GPIO_TEMP_CONT, (_on_true))
|
#define TEMP_CONTROL(_on_true) px4_arch_gpiowrite(GPIO_TEMP_CONT, (_on_true))
|
||||||
|
|
||||||
#define FLASH_BASED_PARAMS
|
#define FLASH_BASED_PARAMS
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
* Public Types
|
* Public Types
|
||||||
****************************************************************************************************/
|
****************************************************************************************************/
|
||||||
@@ -351,4 +351,5 @@ bool board_pwr_button_down(void);
|
|||||||
void board_pwr(bool on_not_off);
|
void board_pwr(bool on_not_off);
|
||||||
|
|
||||||
#endif /* __ASSEMBLY__ */
|
#endif /* __ASSEMBLY__ */
|
||||||
|
|
||||||
__END_DECLS
|
__END_DECLS
|
||||||
|
|||||||
@@ -47,9 +47,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -168,8 +165,7 @@ __BEGIN_DECLS
|
|||||||
|
|
||||||
#define BOARD_FMU_GPIO_TAB { {0, 0, 0}, }
|
#define BOARD_FMU_GPIO_TAB { {0, 0, 0}, }
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
|
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
* Public Types
|
* Public Types
|
||||||
@@ -219,9 +215,6 @@ extern void board_peripheral_reset(int ms);
|
|||||||
int nsh_archinitialize(void);
|
int nsh_archinitialize(void);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* Name: board_i2c_initialize
|
* Name: board_i2c_initialize
|
||||||
*
|
*
|
||||||
@@ -232,7 +225,6 @@ int nsh_archinitialize(void);
|
|||||||
|
|
||||||
int board_i2c_initialize(void);
|
int board_i2c_initialize(void);
|
||||||
|
|
||||||
|
|
||||||
#endif /* __ASSEMBLY__ */
|
#endif /* __ASSEMBLY__ */
|
||||||
|
|
||||||
__END_DECLS
|
__END_DECLS
|
||||||
|
|||||||
@@ -47,9 +47,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -328,6 +325,8 @@ __BEGIN_DECLS
|
|||||||
|
|
||||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
* Public Types
|
* Public Types
|
||||||
****************************************************************************************************/
|
****************************************************************************************************/
|
||||||
|
|||||||
@@ -47,9 +47,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -89,6 +86,8 @@ __BEGIN_DECLS
|
|||||||
|
|
||||||
#define BOARD_NAME "PX4_STM32F4DISCOVERY"
|
#define BOARD_NAME "PX4_STM32F4DISCOVERY"
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
* Public Types
|
* Public Types
|
||||||
****************************************************************************************************/
|
****************************************************************************************************/
|
||||||
|
|||||||
@@ -47,9 +47,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -224,6 +221,8 @@ __BEGIN_DECLS
|
|||||||
*/
|
*/
|
||||||
#define BOARD_HAS_MULTI_PURPOSE_GPIO 1
|
#define BOARD_HAS_MULTI_PURPOSE_GPIO 1
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
* Public Types
|
* Public Types
|
||||||
****************************************************************************************************/
|
****************************************************************************************************/
|
||||||
|
|||||||
@@ -47,9 +47,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -271,8 +268,10 @@ __BEGIN_DECLS
|
|||||||
{GPIO_VDD_5V_PERIPH_OC, 0, 0}, }
|
{GPIO_VDD_5V_PERIPH_OC, 0, 0}, }
|
||||||
|
|
||||||
/* This board provides a DMA pool and APIs */
|
/* This board provides a DMA pool and APIs */
|
||||||
|
|
||||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
* Public Types
|
* Public Types
|
||||||
****************************************************************************************************/
|
****************************************************************************************************/
|
||||||
|
|||||||
@@ -47,9 +47,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -298,9 +295,10 @@ __BEGIN_DECLS
|
|||||||
{GPIO_VDD_BRICK_VALID, 0, 0}, }
|
{GPIO_VDD_BRICK_VALID, 0, 0}, }
|
||||||
|
|
||||||
/* This board provides a DMA pool and APIs */
|
/* This board provides a DMA pool and APIs */
|
||||||
|
|
||||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
* Public Types
|
* Public Types
|
||||||
****************************************************************************************************/
|
****************************************************************************************************/
|
||||||
|
|||||||
@@ -47,7 +47,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
|
|||||||
@@ -47,7 +47,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -143,4 +142,3 @@
|
|||||||
#define LED_SIGNAL 5 /* LED? + LED? */
|
#define LED_SIGNAL 5 /* LED? + LED? */
|
||||||
#define LED_ASSERTION 6 /* LED? + LED? + LED? */
|
#define LED_ASSERTION 6 /* LED? + LED? + LED? */
|
||||||
#define LED_PANIC 7 /* N/C + N/C + N/C + LED? */
|
#define LED_PANIC 7 /* N/C + N/C + N/C + LED? */
|
||||||
|
|
||||||
|
|||||||
@@ -48,9 +48,6 @@
|
|||||||
#include <nuttx/compiler.h>
|
#include <nuttx/compiler.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
@@ -262,6 +259,9 @@ __BEGIN_DECLS
|
|||||||
#define TEMP_CONTROL(_on_true) px4_arch_gpiowrite(GPIO_TEMP_CONT, (_on_true))
|
#define TEMP_CONTROL(_on_true) px4_arch_gpiowrite(GPIO_TEMP_CONT, (_on_true))
|
||||||
|
|
||||||
#define FLASH_BASED_PARAMS
|
#define FLASH_BASED_PARAMS
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/****************************************************************************************************
|
/****************************************************************************************************
|
||||||
* Public Types
|
* Public Types
|
||||||
****************************************************************************************************/
|
****************************************************************************************************/
|
||||||
@@ -320,7 +320,6 @@ extern int board_sdio_initialize(void);
|
|||||||
int nsh_archinitialize(void);
|
int nsh_archinitialize(void);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
/************************************************************************************
|
/************************************************************************************
|
||||||
* Name: board_pwr_init()
|
* Name: board_pwr_init()
|
||||||
*
|
*
|
||||||
@@ -364,4 +363,5 @@ void board_pwr(bool on_not_off);
|
|||||||
int board_i2c_initialize(void);
|
int board_i2c_initialize(void);
|
||||||
|
|
||||||
#endif /* __ASSEMBLY__ */
|
#endif /* __ASSEMBLY__ */
|
||||||
|
|
||||||
__END_DECLS
|
__END_DECLS
|
||||||
|
|||||||
@@ -44,6 +44,9 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <px4_defines.h>
|
#include <px4_defines.h>
|
||||||
|
|
||||||
|
#include "uORB/topics/output_pwm.h"
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <sys/ioctl.h>
|
#include <sys/ioctl.h>
|
||||||
|
|
||||||
@@ -61,7 +64,6 @@ __BEGIN_DECLS
|
|||||||
#define PWM_OUTPUT_BASE_DEVICE_PATH "/dev/pwm_output"
|
#define PWM_OUTPUT_BASE_DEVICE_PATH "/dev/pwm_output"
|
||||||
#define PWM_OUTPUT0_DEVICE_PATH "/dev/pwm_output0"
|
#define PWM_OUTPUT0_DEVICE_PATH "/dev/pwm_output0"
|
||||||
|
|
||||||
#include <uORB/topics/output_pwm.h>
|
|
||||||
#define pwm_output_values output_pwm_s
|
#define pwm_output_values output_pwm_s
|
||||||
|
|
||||||
#ifndef PWM_OUTPUT_MAX_CHANNELS
|
#ifndef PWM_OUTPUT_MAX_CHANNELS
|
||||||
|
|||||||
+2
-1
@@ -45,7 +45,6 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
#include <platforms/px4_defines.h>
|
#include <platforms/px4_defines.h>
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
#include "geo_lookup/geo_mag_declination.h"
|
#include "geo_lookup/geo_mag_declination.h"
|
||||||
|
|
||||||
@@ -79,6 +78,8 @@ struct globallocal_converter_reference_s {
|
|||||||
bool init_done;
|
bool init_done;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Checks if global projection was initialized
|
* Checks if global projection was initialized
|
||||||
* @return true if map was initialized before, false else
|
* @return true if map was initialized before, false else
|
||||||
|
|||||||
@@ -42,8 +42,6 @@
|
|||||||
#ifndef MAVLINK_BRIDGE_HEADER_H
|
#ifndef MAVLINK_BRIDGE_HEADER_H
|
||||||
#define MAVLINK_BRIDGE_HEADER_H
|
#define MAVLINK_BRIDGE_HEADER_H
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
/* use efficient approach, see mavlink_helpers.h */
|
/* use efficient approach, see mavlink_helpers.h */
|
||||||
@@ -57,6 +55,7 @@ __BEGIN_DECLS
|
|||||||
#include <v2.0/mavlink_types.h>
|
#include <v2.0/mavlink_types.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/* Struct that stores the communication settings of this system.
|
/* Struct that stores the communication settings of this system.
|
||||||
you can also define / alter these settings elsewhere, as long
|
you can also define / alter these settings elsewhere, as long
|
||||||
|
|||||||
@@ -35,8 +35,6 @@
|
|||||||
|
|
||||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
#include <sched.h>
|
#include <sched.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
@@ -58,6 +56,8 @@ struct system_load_s {
|
|||||||
int sleeping_count;
|
int sleeping_count;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
__EXPORT extern struct system_load_s system_load;
|
__EXPORT extern struct system_load_s system_load;
|
||||||
|
|
||||||
__EXPORT void cpuload_initialize_once(void);
|
__EXPORT void cpuload_initialize_once(void);
|
||||||
|
|||||||
@@ -43,8 +43,6 @@
|
|||||||
#ifndef OTP_H_
|
#ifndef OTP_H_
|
||||||
#define OTP_H_
|
#define OTP_H_
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
#define ADDR_OTP_START 0x1FFF7800
|
#define ADDR_OTP_START 0x1FFF7800
|
||||||
#define ADDR_OTP_LOCK_START 0x1FFF7A00
|
#define ADDR_OTP_LOCK_START 0x1FFF7A00
|
||||||
|
|
||||||
@@ -130,6 +128,7 @@ union udid {
|
|||||||
};
|
};
|
||||||
#pragma pack(pop)
|
#pragma pack(pop)
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* s
|
* s
|
||||||
|
|||||||
@@ -41,9 +41,8 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
#include <px4_config.h>
|
#include <px4_config.h>
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
#ifndef CONFIG_MAX_TASKS
|
#ifndef CONFIG_MAX_TASKS
|
||||||
@@ -63,6 +62,8 @@ struct print_load_s {
|
|||||||
float interval_time_ms_inv;
|
float interval_time_ms_inv;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
__EXPORT void init_print_load_s(uint64_t t, struct print_load_s *s);
|
__EXPORT void init_print_load_s(uint64_t t, struct print_load_s *s);
|
||||||
|
|
||||||
__EXPORT void print_load(uint64_t t, int fd, struct print_load_s *print_state);
|
__EXPORT void print_load(uint64_t t, int fd, struct print_load_s *print_state);
|
||||||
|
|||||||
Reference in New Issue
Block a user