mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: Fix includes
This commit is contained in:
parent
dfd81da149
commit
8cafbe394f
|
@ -1,4 +1,5 @@
|
|||
#include "GCS.h"
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -11,18 +11,13 @@
|
|||
#include <stdint.h>
|
||||
#include "MAVLink_routing.h"
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_Mount/AP_Mount.h>
|
||||
#include <AP_Avoidance/AP_Avoidance.h>
|
||||
#include <AP_Proximity/AP_Proximity.h>
|
||||
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
||||
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
|
||||
#include <AP_Camera/AP_Camera.h>
|
||||
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
#include <AP_RTC/JitterCorrection.h>
|
||||
#include <AP_Common/Bitmask.h>
|
||||
#include <AP_Devo_Telem/AP_Devo_Telem.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
|
||||
#define GCS_DEBUG_SEND_MESSAGE_TIMINGS 0
|
||||
|
||||
|
|
|
@ -22,10 +22,13 @@
|
|||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_RangeFinder/RangeFinder_Backend.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_Camera/AP_Camera.h>
|
||||
#include <AP_Gripper/AP_Gripper.h>
|
||||
#include <AP_BLHeli/AP_BLHeli.h>
|
||||
#include <AP_Common/Semaphore.h>
|
||||
#include <AP_Scheduler/AP_Scheduler.h>
|
||||
#include <AP_Mount/AP_Mount.h>
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
|
||||
#include "GCS.h"
|
||||
|
|
|
@ -1,4 +1,5 @@
|
|||
#include "GCS.h"
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
|
||||
const AP_FWVersion AP_FWVersion::fwver
|
||||
{
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
|
||||
#include "AP_Common/AP_FWVersion.h"
|
||||
#include "GCS.h"
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
|
|
@ -16,6 +16,7 @@
|
|||
*/
|
||||
|
||||
#include "GCS.h"
|
||||
#include <AP_Rally/AP_Rally.h>
|
||||
|
||||
void GCS_MAVLINK::handle_rally_point(mavlink_message_t *msg)
|
||||
{
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
|
||||
void setup();
|
||||
void loop();
|
||||
|
|
Loading…
Reference in New Issue