Commander: Allow arming a rover with the throttle stick in the middle

This commit is contained in:
Matthias Grob 2021-11-17 22:24:26 +01:00
parent 02336acd61
commit 4c6621f6cf

View File

@ -576,7 +576,7 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_
}
if (!_vehicle_control_mode.flag_control_climb_rate_enabled &&
!_status.rc_signal_lost && !_is_throttle_low) {
!_status.rc_signal_lost && !_is_throttle_low && _status.vehicle_type != vehicle_status_s::VEHICLE_TYPE_ROVER) {
mavlink_log_critical(&_mavlink_log_pub, "Arming denied: high throttle\t");
events::send(events::ID("commander_arm_denied_throttle_high"),
{events::Log::Critical, events::LogInternal::Info},