diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index f14f7830f8..e31b050d3f 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -303,6 +303,15 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Values: 0:Disabled,1:Enabled // @User: Standard AP_GROUPINFO("GUIDED_MODE", 40, QuadPlane, guided_mode, 0), + + // @Param: THR_MIN + // @DisplayName: Throttle Minimum + // @Description: The minimum throttle that will be sent to the motors to keep them spinning + // @Units: Percent*10 + // @Range: 0 300 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("THR_MIN", 41, QuadPlane, throttle_min, 100), AP_GROUPEND }; @@ -418,7 +427,7 @@ bool QuadPlane::setup(void) motors->set_frame_orientation(frame_type); motors->Init(); - motors->set_throttle_range(100, thr_min_pwm, thr_max_pwm); + motors->set_throttle_range(throttle_min, thr_min_pwm, thr_max_pwm); motors->set_hover_throttle(throttle_mid); motors->set_update_rate(rc_speed); motors->set_interlock(true); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 34c3b61256..37b33067d8 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -80,7 +80,7 @@ public: // return current throttle as a percentate uint8_t throttle_percentage(void) const { - return last_throttle * 0.1f; + return last_throttle * 100; } // return desired forward throttle percentage @@ -194,6 +194,7 @@ private: AP_Int16 thr_min_pwm; AP_Int16 thr_max_pwm; AP_Int16 throttle_mid; + AP_Int16 throttle_min; // speed below which quad assistance is given AP_Float assist_speed;