Browse Source

GCS_MAVLink: remove include of AP_Param.h in GCS_MAVLink.h

This will help break include loops.
mission-4.1.18
Peter Barker 6 years ago committed by Peter Barker
parent
commit
210c2070a1
  1. 3
      libraries/GCS_MAVLink/GCS.h
  2. 2
      libraries/GCS_MAVLink/GCS_MAVLink.cpp
  3. 5
      libraries/GCS_MAVLink/GCS_MAVLink.h
  4. 2
      libraries/GCS_MAVLink/GCS_Param.cpp

3
libraries/GCS_MAVLink/GCS.h

@ -516,6 +516,9 @@ protected: @@ -516,6 +516,9 @@ protected:
virtual MAV_VTOL_STATE vtol_state() const { return MAV_VTOL_STATE_UNDEFINED; }
virtual MAV_LANDED_STATE landed_state() const { return MAV_LANDED_STATE_UNDEFINED; }
// return a MAVLink parameter type given a AP_Param type
static MAV_PARAM_TYPE mav_param_type(enum ap_var_type t);
AP_Param * _queued_parameter; ///< next parameter to
// be sent in queue
mavlink_channel_t chan;

2
libraries/GCS_MAVLink/GCS_MAVLink.cpp

@ -76,7 +76,7 @@ void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan) @@ -76,7 +76,7 @@ void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan)
}
// return a MAVLink parameter type given a AP_Param type
MAV_PARAM_TYPE mav_param_type(enum ap_var_type t)
MAV_PARAM_TYPE GCS_MAVLINK::mav_param_type(enum ap_var_type t)
{
if (t == AP_PARAM_INT8) {
return MAV_PARAM_TYPE_INT8;

5
libraries/GCS_MAVLink/GCS_MAVLink.h

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
/// @brief One size fits all header for MAVLink integration.
#pragma once
#include <AP_Param/AP_Param.h>
#include <AP_HAL/AP_HAL_Boards.h>
// we have separate helpers disabled to make it possible
// to select MAVLink 1.0 in the arduino GUI build
@ -76,9 +76,6 @@ uint16_t comm_get_txspace(mavlink_channel_t chan); @@ -76,9 +76,6 @@ uint16_t comm_get_txspace(mavlink_channel_t chan);
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#include "include/mavlink/v2.0/ardupilotmega/mavlink.h"
// return a MAVLink parameter type given a AP_Param type
MAV_PARAM_TYPE mav_param_type(enum ap_var_type t);
// lock and unlock a channel, for multi-threaded mavlink send
void comm_send_lock(mavlink_channel_t chan);
void comm_send_unlock(mavlink_channel_t chan);

2
libraries/GCS_MAVLink/GCS_Param.cpp

@ -308,7 +308,7 @@ void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, f @@ -308,7 +308,7 @@ void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, f
const uint8_t to_copy = MIN(ARRAY_SIZE(packet.param_id), strlen(param_name));
memcpy(packet.param_id, param_name, to_copy);
packet.param_value = param_value;
packet.param_type = mav_param_type(param_type);
packet.param_type = GCS_MAVLINK::mav_param_type(param_type);
packet.param_count = AP_Param::count_parameters();
packet.param_index = -1;

Loading…
Cancel
Save