mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: include cleanups
This commit is contained in:
parent
e93be25ed4
commit
7638cbf001
@ -7,8 +7,14 @@
|
||||
#include <AP_Scheduler/AP_Scheduler.h>
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Compass/AP_Compass.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_Arming/AP_Arming.h>
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
|
||||
#include "MissionItemProtocol_Waypoints.h"
|
||||
#include "MissionItemProtocol_Rally.h"
|
||||
#include "MissionItemProtocol_Fence.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -17,21 +17,14 @@
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
#include <stdint.h>
|
||||
#include "MAVLink_routing.h"
|
||||
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
||||
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
|
||||
#include <AP_RTC/JitterCorrection.h>
|
||||
#include <AP_Common/Bitmask.h>
|
||||
#include <AP_LTM_Telem/AP_LTM_Telem.h>
|
||||
#include <AP_Devo_Telem/AP_Devo_Telem.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <AP_Filesystem/AP_Filesystem_Available.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||
|
||||
#include "MissionItemProtocol_Waypoints.h"
|
||||
#include "MissionItemProtocol_Rally.h"
|
||||
#include "MissionItemProtocol_Fence.h"
|
||||
#include "ap_message.h"
|
||||
|
||||
#define GCS_DEBUG_SEND_MESSAGE_TIMINGS 0
|
||||
@ -611,7 +604,7 @@ protected:
|
||||
static constexpr const float magic_force_arm_value = 2989.0f;
|
||||
static constexpr const float magic_force_disarm_value = 21196.0f;
|
||||
|
||||
void manual_override(RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false);
|
||||
void manual_override(class RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false);
|
||||
|
||||
uint8_t receiver_rssi() const;
|
||||
|
||||
@ -1051,10 +1044,10 @@ public:
|
||||
ap_var_type param_type,
|
||||
float param_value);
|
||||
|
||||
static MissionItemProtocol_Waypoints *_missionitemprotocol_waypoints;
|
||||
static MissionItemProtocol_Rally *_missionitemprotocol_rally;
|
||||
static MissionItemProtocol_Fence *_missionitemprotocol_fence;
|
||||
MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const;
|
||||
static class MissionItemProtocol_Waypoints *_missionitemprotocol_waypoints;
|
||||
static class MissionItemProtocol_Rally *_missionitemprotocol_rally;
|
||||
static class MissionItemProtocol_Fence *_missionitemprotocol_fence;
|
||||
class MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const;
|
||||
void try_send_queued_message_for_type(MAV_MISSION_TYPE type) const;
|
||||
|
||||
void update_send();
|
||||
@ -1075,7 +1068,7 @@ public:
|
||||
bool out_of_time() const;
|
||||
|
||||
// frsky backend
|
||||
AP_Frsky_Telem *frsky;
|
||||
class AP_Frsky_Telem *frsky;
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
// LTM backend
|
||||
|
@ -18,6 +18,7 @@
|
||||
|
||||
#include <AC_Fence/AC_Fence.h>
|
||||
#include <AP_ADSB/AP_ADSB.h>
|
||||
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Arming/AP_Arming.h>
|
||||
@ -49,6 +50,13 @@
|
||||
#include <AP_RCTelemetry/AP_CRSF_Telem.h>
|
||||
#include <AP_AIS/AP_AIS.h>
|
||||
#include <AP_Filesystem/AP_Filesystem.h>
|
||||
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
|
||||
#include "MissionItemProtocol_Waypoints.h"
|
||||
#include "MissionItemProtocol_Rally.h"
|
||||
#include "MissionItemProtocol_Fence.h"
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
|
@ -1,6 +1,8 @@
|
||||
#include "MissionItemProtocol_Fence.h"
|
||||
|
||||
#include <AC_Fence/AC_Fence.h>
|
||||
#include <AP_InternalError/AP_InternalError.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
/*
|
||||
public function to format mission item as mavlink_mission_item_int_t
|
||||
|
Loading…
Reference in New Issue
Block a user