Browse Source

GCS_MAVLink: updates for 24 bit msgid

master
Andrew Tridgell 9 years ago
parent
commit
006b9728d0
  1. 2
      libraries/GCS_MAVLink/GCS_Logs.cpp
  2. 14
      libraries/GCS_MAVLink/GCS_Signing.cpp
  3. 2
      libraries/GCS_MAVLink/GCS_serial_control.cpp

2
libraries/GCS_MAVLink/GCS_Logs.cpp

@ -239,7 +239,7 @@ bool GCS_MAVLINK::handle_log_send_data(DataFlash_Class &dataflash) @@ -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_TUPLE, (const char *)&packet,
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet,
MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
_log_data_offset += len;

14
libraries/GCS_MAVLink/GCS_Signing.cpp

@ -84,15 +84,12 @@ void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t *msg) @@ -84,15 +84,12 @@ void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t *msg)
*/
extern "C" {
static const struct {
uint8_t dialect;
uint16_t msgId;
} accept_list[] = {
{ MAVLINK_MSG_ID_RADIO_STATUS_TUPLE }
static const uint32_t accept_list[] = {
MAVLINK_MSG_ID_RADIO_STATUS,
MAVLINK_MSG_ID_RADIO
};
static bool accept_unsigned_callback(const mavlink_status_t *status,
uint8_t dialect, uint16_t msgId)
static bool accept_unsigned_callback(const mavlink_status_t *status, uint32_t msgId)
{
if (status == mavlink_get_channel_status(MAVLINK_COMM_0)) {
// always accept channel 0, assumed to be secure channel. This
@ -100,8 +97,7 @@ static bool accept_unsigned_callback(const mavlink_status_t *status, @@ -100,8 +97,7 @@ static bool accept_unsigned_callback(const mavlink_status_t *status,
return true;
}
for (uint8_t i=0; i<ARRAY_SIZE(accept_list); i++) {
if (accept_list[i].dialect == dialect &&
accept_list[i].msgId == msgId) {
if (accept_list[i] == msgId) {
return true;
}
}

2
libraries/GCS_MAVLink/GCS_serial_control.cpp

@ -152,7 +152,7 @@ more_data: @@ -152,7 +152,7 @@ more_data:
// and send the reply
_mav_finalize_message_chan_send(chan,
MAVLINK_MSG_ID_SERIAL_CONTROL_TUPLE,
MAVLINK_MSG_ID_SERIAL_CONTROL,
(const char *)&packet,
MAVLINK_MSG_ID_SERIAL_CONTROL_LEN,
MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);

Loading…
Cancel
Save