Plane: added Q_THR_MIN

This commit is contained in:
Andrew Tridgell 2016-05-08 08:11:00 +10:00
parent 45609bb568
commit 52ea443d65
2 changed files with 12 additions and 2 deletions

View File

@ -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);

View File

@ -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;