mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
GCS_MAVLink: record mavlink msg IDs for watchdog
This commit is contained in:
parent
8d0bca6ba9
commit
64c723fd31
@ -1507,6 +1507,7 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us)
|
|||||||
|
|
||||||
// Try to get a new message
|
// Try to get a new message
|
||||||
if (mavlink_parse_char(chan, c, &msg, &status)) {
|
if (mavlink_parse_char(chan, c, &msg, &status)) {
|
||||||
|
hal.util->persistent_data.last_mavlink_msgid = msg.msgid;
|
||||||
hal.util->perf_begin(_perf_packet);
|
hal.util->perf_begin(_perf_packet);
|
||||||
packetReceived(status, msg);
|
packetReceived(status, msg);
|
||||||
hal.util->perf_end(_perf_packet);
|
hal.util->perf_end(_perf_packet);
|
||||||
@ -3737,6 +3738,8 @@ void GCS_MAVLINK::handle_command_long(mavlink_message_t *msg)
|
|||||||
mavlink_command_long_t packet;
|
mavlink_command_long_t packet;
|
||||||
mavlink_msg_command_long_decode(msg, &packet);
|
mavlink_msg_command_long_decode(msg, &packet);
|
||||||
|
|
||||||
|
hal.util->persistent_data.last_mavlink_cmd = packet.command;
|
||||||
|
|
||||||
const MAV_RESULT result = handle_command_long_packet(packet);
|
const MAV_RESULT result = handle_command_long_packet(packet);
|
||||||
|
|
||||||
// send ACK or NAK
|
// send ACK or NAK
|
||||||
@ -3854,6 +3857,8 @@ void GCS_MAVLINK::handle_command_int(mavlink_message_t *msg)
|
|||||||
mavlink_command_int_t packet;
|
mavlink_command_int_t packet;
|
||||||
mavlink_msg_command_int_decode(msg, &packet);
|
mavlink_msg_command_int_decode(msg, &packet);
|
||||||
|
|
||||||
|
hal.util->persistent_data.last_mavlink_cmd = packet.command;
|
||||||
|
|
||||||
const MAV_RESULT result = handle_command_int_packet(packet);
|
const MAV_RESULT result = handle_command_int_packet(packet);
|
||||||
|
|
||||||
// send ACK or NAK
|
// send ACK or NAK
|
||||||
|
Loading…
Reference in New Issue
Block a user