mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: populate sysid/compid in reboot ACK
This commit is contained in:
parent
3ced1b27aa
commit
c8a1fff8ae
@ -503,7 +503,7 @@ protected:
|
||||
void handle_common_message(const mavlink_message_t &msg);
|
||||
void handle_set_gps_global_origin(const mavlink_message_t &msg);
|
||||
void handle_setup_signing(const mavlink_message_t &msg) const;
|
||||
virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet);
|
||||
virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg);
|
||||
|
||||
// reset a message interval via mavlink:
|
||||
MAV_RESULT handle_command_set_message_interval(const mavlink_command_long_t &packet);
|
||||
|
@ -2907,7 +2907,7 @@ void GCS_MAVLINK::send_vfr_hud()
|
||||
motors. That can be dangerous when a preflight reboot is done with
|
||||
the pilot close to the aircraft and can also damage the aircraft
|
||||
*/
|
||||
MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
|
||||
{
|
||||
if (is_equal(packet.param1, 42.0f) &&
|
||||
is_equal(packet.param2, 24.0f) &&
|
||||
@ -3004,7 +3004,9 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
|
||||
|
||||
// send ack before we reboot
|
||||
mavlink_msg_command_ack_send(chan, packet.command, MAV_RESULT_ACCEPTED,
|
||||
0, 0, 0, 0);
|
||||
0, 0,
|
||||
msg.sysid,
|
||||
msg.compid);
|
||||
|
||||
// when packet.param1 == 3 we reboot to hold in bootloader
|
||||
const bool hold_in_bootloader = is_equal(packet.param1, 3.0f);
|
||||
@ -4533,10 +4535,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
||||
result = handle_command_do_fence_enable(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
result = handle_preflight_reboot(packet);
|
||||
break;
|
||||
|
||||
#if HAL_HIGH_LATENCY2_ENABLED
|
||||
case MAV_CMD_CONTROL_HIGH_LATENCY:
|
||||
result = handle_control_high_latency(packet);
|
||||
@ -4779,6 +4777,10 @@ void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg)
|
||||
result = handle_can_forward(packet, msg);
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
result = handle_preflight_reboot(packet, msg);
|
||||
break;
|
||||
|
||||
default:
|
||||
result = handle_command_long_packet(packet);
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user