Skip to content

Commit

Permalink
Copter: Clearly show the preprocessor
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Jun 19, 2024
1 parent f89923f commit 3132367
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -597,11 +597,11 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)

// check throttle
if (check_enabled(ARMING_CHECK_RC)) {
#if FRAME_CONFIG == HELI_FRAME
#if FRAME_CONFIG == HELI_FRAME
const char *rc_item = "Collective";
#else
#else
const char *rc_item = "Throttle";
#endif
#endif
// check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto
if (!((AP_Arming::method_is_GCS(method) || 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
Expand All @@ -610,12 +610,12 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
return false;
}
// in manual modes throttle must be at zero
#if FRAME_CONFIG != HELI_FRAME
#if FRAME_CONFIG != HELI_FRAME
if ((copter.flightmode->has_manual_throttle() || copter.flightmode->mode_number() == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
return false;
}
#endif
#endif
}
}

Expand Down

0 comments on commit 3132367

Please sign in to comment.