mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: support mavlink2 build
This commit is contained in:
parent
0ef5d8995b
commit
0ead0ab978
@ -239,7 +239,7 @@ bool GCS_MAVLINK::handle_log_send_data(DataFlash_Class &dataflash)
|
||||
packet.ofs = _log_data_offset;
|
||||
packet.id = _log_num_data;
|
||||
packet.count = ret;
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet,
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA_TUPLE, (const char *)&packet,
|
||||
MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
|
||||
|
||||
_log_data_offset += len;
|
||||
|
@ -29,8 +29,12 @@ 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];
|
||||
|
||||
@ -144,14 +148,6 @@ void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
|
||||
mavlink_comm_port[chan]->write(buf, len);
|
||||
}
|
||||
|
||||
static const uint8_t mavlink_message_crc_table[256] = MAVLINK_MESSAGE_CRCS;
|
||||
|
||||
// return CRC byte for a mavlink message ID
|
||||
uint8_t mavlink_get_message_crc(uint8_t msgid)
|
||||
{
|
||||
return mavlink_message_crc_table[msgid];
|
||||
}
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/*
|
||||
|
@ -14,10 +14,6 @@
|
||||
|
||||
#define MAVLINK_SEND_UART_BYTES(chan, buf, len) comm_send_buffer(chan, buf, len)
|
||||
|
||||
// define our own MAVLINK_MESSAGE_CRC() macro to allow it to be put
|
||||
// into progmem
|
||||
#define MAVLINK_MESSAGE_CRC(msgid) mavlink_get_message_crc(msgid)
|
||||
|
||||
// allow five telemetry ports
|
||||
#define MAVLINK_COMM_NUM_BUFFERS 5
|
||||
|
||||
@ -28,11 +24,19 @@
|
||||
#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];
|
||||
@ -93,12 +97,13 @@ 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);
|
||||
|
||||
// return CRC byte for a mavlink message ID
|
||||
uint8_t mavlink_get_message_crc(uint8_t msgid);
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
|
@ -152,7 +152,7 @@ more_data:
|
||||
|
||||
// and send the reply
|
||||
_mav_finalize_message_chan_send(chan,
|
||||
MAVLINK_MSG_ID_SERIAL_CONTROL,
|
||||
MAVLINK_MSG_ID_SERIAL_CONTROL_TUPLE,
|
||||
(const char *)&packet,
|
||||
MAVLINK_MSG_ID_SERIAL_CONTROL_LEN,
|
||||
MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
|
||||
|
Loading…
Reference in New Issue
Block a user