ArduSub: 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 a0ca3ffb22
commit 2eb5a7b09d
2 changed files with 2 additions and 2 deletions

View File

@ -799,7 +799,7 @@ uint64_t GCS_MAVLINK_Sub::capabilities() const
);
}
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) {
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_int_t &packet) {
if (packet.param1 > 0.5f) {
sub.arming.disarm(AP_Arming::Method::TERMINATION);
return MAV_RESULT_ACCEPTED;

View File

@ -15,7 +15,7 @@ protected:
return 0;
};
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override;
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;