mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Add missing header files.
These headers files were missing from the header files that I added them to; the fact that they were missing didn't lead to compile errors because by coincidence the missing headers are included in the source files before including these headers. But, after the reordering of header inclusions by Tools/fix_headers.sh, these cases will give rise to compiler errors.
This commit is contained in:
parent
86c581b2ef
commit
04aa2bb3a4
@ -33,6 +33,9 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/device/ringbuffer.h" // ringbuffer::RingBuffer
|
||||
#include "drivers/drv_mag.h" // mag_calibration_s
|
||||
#include "systemlib/perf_counter.h" // perf_counter_t
|
||||
|
||||
/* in 16-bit sampling mode the mag resolution is 1.5 milli Gauss per bit */
|
||||
|
||||
|
||||
@ -43,6 +43,7 @@
|
||||
|
||||
#include "Block.hpp"
|
||||
#include <containers/List.hpp>
|
||||
#include <cstddef> // NULL
|
||||
|
||||
namespace control
|
||||
{
|
||||
|
||||
@ -46,6 +46,8 @@
|
||||
#include <stdio.h>
|
||||
#include <cmath>
|
||||
|
||||
#include "Vector.hpp" // Vector and eigen_matrix_instance
|
||||
|
||||
#include "matrix/math.hpp"
|
||||
#include <platforms/px4_defines.h>
|
||||
|
||||
|
||||
@ -52,6 +52,7 @@
|
||||
#define MAVLINK_GET_CHANNEL_BUFFER mavlink_get_channel_buffer
|
||||
#define MAVLINK_GET_CHANNEL_STATUS mavlink_get_channel_status
|
||||
|
||||
#include <stdbool.h> // Needs to be included before v2.0/mavlink_types.h until https://github.com/ArduPilot/pymavlink/pull/22 makes it through.
|
||||
#include <v2.0/mavlink_types.h>
|
||||
#include <unistd.h>
|
||||
|
||||
|
||||
@ -40,6 +40,7 @@
|
||||
#include <queue.h>
|
||||
#include <time.h>
|
||||
#include <stdio.h>
|
||||
#include <cstdbool>
|
||||
#include <v2.0/mavlink_types.h>
|
||||
#include "mavlink_stream.h"
|
||||
|
||||
|
||||
@ -43,7 +43,7 @@
|
||||
|
||||
#include <systemlib/uthash/utlist.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include "uORB/uORB.h" // orb_id_t
|
||||
|
||||
class MavlinkOrbSubscription
|
||||
{
|
||||
|
||||
@ -47,6 +47,7 @@
|
||||
#include <poll.h>
|
||||
#include <signal.h>
|
||||
#include <crc32.h>
|
||||
#include <syslog.h>
|
||||
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
@ -42,6 +42,8 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h> // uint8_t
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
__EXPORT int get_board_serial(uint8_t *serialid);
|
||||
|
||||
@ -37,6 +37,7 @@
|
||||
|
||||
#include <sched.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
struct system_load_taskinfo_s {
|
||||
uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load
|
||||
|
||||
@ -41,6 +41,8 @@
|
||||
|
||||
#include <uavcan/node/sub_node.hpp>
|
||||
#include <uavcan/protocol/node_status_monitor.hpp>
|
||||
#include <uavcan/protocol/param/GetSet.hpp>
|
||||
#include <uavcan/protocol/param/ExecuteOpcode.hpp>
|
||||
|
||||
#include <uavcan/protocol/dynamic_node_id_server/centralized.hpp>
|
||||
#include <uavcan/protocol/node_info_retriever.hpp>
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user