mirror of https://github.com/ArduPilot/ardupilot
Blimp: handle MAV_CMD_DO_FLIGHTTERMINATION as both long and int
This commit is contained in:
parent
2eb5a7b09d
commit
eb0d421bfc
|
@ -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) {
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue