Blimp: handle MAV_CMD_DO_FLIGHTTERMINATION as both long and int

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

View File

@ -529,7 +529,7 @@ void GCS_MAVLINK_Blimp::handleMessage(const mavlink_message_t &msg)
} // end handle mavlink
MAV_RESULT GCS_MAVLINK_Blimp::handle_flight_termination(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK_Blimp::handle_flight_termination(const mavlink_command_int_t &packet)
{
MAV_RESULT result = MAV_RESULT_FAILED;
if (packet.param1 > 0.5f) {

View File

@ -13,7 +13,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;