Copter: Allow arming in guided mode from scripting

This commit is contained in:
Stephen Dade 2022-12-22 15:05:40 +11:00 committed by Peter Barker
parent a3cdfd0e3c
commit b23f5e380c
2 changed files with 4 additions and 4 deletions

View File

@ -628,8 +628,8 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
#else #else
const char *rc_item = "Throttle"; const char *rc_item = "Throttle";
#endif #endif
// check throttle is not too high - skips checks if arming from GCS in Guided,Guided_NoGPS or Auto // check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto
if (!(method == AP_Arming::Method::MAVLINK && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS || copter.flightmode->mode_number() == Mode::Number::AUTO))) { if (!((method == AP_Arming::Method::MAVLINK || method == AP_Arming::Method::SCRIPTING) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS || copter.flightmode->mode_number() == Mode::Number::AUTO))) {
// above top of deadband is too always high // above top of deadband is too always high
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) { if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item); check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);

View File

@ -99,8 +99,8 @@ void ModeGuided::run()
bool ModeGuided::allows_arming(AP_Arming::Method method) const bool ModeGuided::allows_arming(AP_Arming::Method method) const
{ {
// always allow arming from the ground station // always allow arming from the ground station or scripting
if (method == AP_Arming::Method::MAVLINK) { if (method == AP_Arming::Method::MAVLINK || method == AP_Arming::Method::SCRIPTING) {
return true; return true;
} }