Sub: Support common version of MAV_CMD_DO_FLIGHT_TERMINATION

This commit is contained in:
Michael du Breuil 2017-07-26 22:23:40 -07:00 committed by Francisco Ferreira
parent 105ebd6fb0
commit 6e55c9554a
2 changed files with 12 additions and 7 deletions

View File

@ -1027,13 +1027,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_DO_FLIGHTTERMINATION:
if (packet.param1 > 0.5f) {
sub.init_disarm_motors();
result = MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_DO_SET_ROI:
// param1 : regional of interest mode (not supported)
// param2 : mission index/ target id (not supported)
@ -1608,3 +1601,14 @@ AP_Rally *GCS_MAVLINK_Sub::get_rally() const
return nullptr;
#endif
}
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) {
if (packet.param1 > 0.5f) {
sub.init_disarm_motors();
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
}
// dummy method to avoid linking AFS
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate) { return false; }

View File

@ -20,6 +20,7 @@ protected:
AP_Camera *get_camera() const override;
AP_ServoRelayEvents *get_servorelayevents() const override;
AP_GPS *get_gps() const override;
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
uint8_t sysid_my_gcs() const override;