GCS_MAVLink: always build with MAVLink2 headers

This commit is contained in:
Andrew Tridgell 2016-05-16 11:37:43 +10:00
parent f377787444
commit b3f94184f2
5 changed files with 0 additions and 36 deletions

View File

@ -357,7 +357,6 @@ private:
// return true if this channel has hardware flow control
bool have_flow_control(void);
#if MAVLINK_PROTOCOL_VERSION >= 2
mavlink_signing_t signing;
static mavlink_signing_streams_t signing_streams;
static uint32_t last_signing_save_ms;
@ -370,9 +369,4 @@ private:
bool signing_enabled(void) const;
uint8_t packet_overhead(void) const { return packet_overhead_chan(chan); }
static void save_signing_timestamp(bool force_save_now);
#else
bool signing_enabled(void) const { return false; }
uint8_t packet_overhead(void) const { return MAVLINK_NUM_NON_PAYLOAD_BYTES; }
static void save_signing_timestamp(bool force_save_now) {}
#endif // MAVLINK_PROTOCOL_VERSION
};

View File

@ -101,7 +101,6 @@ GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager
// and init the gcs instance
init(uart, mav_chan);
#if MAVLINK_PROTOCOL_VERSION >= 2
// load signing key
load_signing_key();
@ -113,7 +112,6 @@ GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager
// after experiments with MAVLink2
status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
}
#endif
}
/**
@ -940,7 +938,6 @@ GCS_MAVLINK::update(run_cli_fn run_cli)
if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
mavlink_active |= (1U<<(chan-MAVLINK_COMM_0));
}
#if MAVLINK_PROTOCOL_VERSION >= 2
if (!(status.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) &&
(status.flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
// if we receive any MAVLink2 packets on a connection
@ -951,7 +948,6 @@ GCS_MAVLINK::update(run_cli_fn run_cli)
cstatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
}
}
#endif
// if a snoop handler has been setup then use it
if (msg_snoop != NULL) {
msg_snoop(&msg);

View File

@ -29,11 +29,7 @@ This provides some support code and variables for MAVLink enabled sketches
#ifdef MAVLINK_SEPARATE_HELPERS
#if MAVLINK_PROTOCOL_VERSION == 2
#include "include/mavlink/v2.0/mavlink_helpers.h"
#else
#include "include/mavlink/v1.0/mavlink_helpers.h"
#endif
#endif
AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS];

View File

@ -24,19 +24,11 @@
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcast-align"
#if MAVLINK_PROTOCOL_VERSION == 2
#include "include/mavlink/v2.0/ardupilotmega/version.h"
#else
#include "include/mavlink/v1.0/ardupilotmega/version.h"
#endif
#define MAVLINK_MAX_PAYLOAD_LEN 255
#if MAVLINK_PROTOCOL_VERSION == 2
#include "include/mavlink/v2.0/mavlink_types.h"
#else
#include "include/mavlink/v1.0/mavlink_types.h"
#endif
/// MAVLink stream used for uartA
extern AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS];
@ -97,11 +89,7 @@ uint16_t comm_get_txspace(mavlink_channel_t chan);
bool comm_is_idle(mavlink_channel_t chan);
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#if MAVLINK_PROTOCOL_VERSION == 2
#include "include/mavlink/v2.0/ardupilotmega/mavlink.h"
#else
#include "include/mavlink/v1.0/ardupilotmega/mavlink.h"
#endif
// return a MAVLink variable type given a AP_Param type
uint8_t mav_var_type(enum ap_var_type t);

View File

@ -21,8 +21,6 @@
extern const AP_HAL::HAL& hal;
#if MAVLINK_PROTOCOL_VERSION >= 2
// storage object
StorageAccess GCS_MAVLINK::_signing_storage(StorageManager::StorageKeys);
@ -243,11 +241,3 @@ uint8_t GCS_MAVLINK::packet_overhead_chan(mavlink_channel_t chan)
return MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
#else
void GCS_MAVLINK::update_signing_timestamp(uint64_t timestamp_usec) {}
uint8_t GCS_MAVLINK::packet_overhead_chan(mavlink_channel_t chan)
{
return MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
#endif // MAVLINK_PROTOCOL_VERSION