ArduCopter: handle MAV_CMD_DO_FLIGHTTERMINATION as both long and int

This commit is contained in:
Peter Barker 2023-09-26 16:25:01 +10:00 committed by Tom Pittenger
parent ef8cd449ec
commit a0ca3ffb22
2 changed files with 2 additions and 2 deletions

View File

@ -1478,7 +1478,7 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
} // end handle mavlink
MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_long_t &packet) {
MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) {
#if ADVANCED_FAILSAFE == ENABLED
if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) {
return MAV_RESULT_ACCEPTED;

View File

@ -18,7 +18,7 @@ protected:
uint32_t telem_delay() const override;
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override;
uint8_t sysid_my_gcs() const override;
bool sysid_enforce() const override;