mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: added MOT_SPOOL_TIME
this allows for quadplanes to have faster spoolup, which can help with transitions
This commit is contained in:
parent
18b5446765
commit
2187417d74
|
@ -153,6 +153,15 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("YAW_SV_ANGLE", 35, AP_MotorsMulticopter, _yaw_servo_angle_max_deg, 30),
|
AP_GROUPINFO("YAW_SV_ANGLE", 35, AP_MotorsMulticopter, _yaw_servo_angle_max_deg, 30),
|
||||||
|
|
||||||
|
// @Param: SPOOL_TIME
|
||||||
|
// @DisplayName: Spool up time
|
||||||
|
// @Description: Time in seconds to spool up the motors from zero to min throttle.
|
||||||
|
// @Range: 0 2
|
||||||
|
// @Units: Seconds
|
||||||
|
// @Increment: 0.1
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("SPOOL_TIME", 36, AP_MotorsMulticopter, _spool_up_time, AP_MOTORS_SPOOL_UP_TIME_DEFAULT),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
@ -415,6 +424,11 @@ void AP_MotorsMulticopter::output_logic()
|
||||||
_spool_mode = SHUT_DOWN;
|
_spool_mode = SHUT_DOWN;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (_spool_up_time < 0.05) {
|
||||||
|
// prevent float exception
|
||||||
|
_spool_up_time.set(0.05);
|
||||||
|
}
|
||||||
|
|
||||||
switch (_spool_mode) {
|
switch (_spool_mode) {
|
||||||
case SHUT_DOWN:
|
case SHUT_DOWN:
|
||||||
// Motors should be stationary.
|
// Motors should be stationary.
|
||||||
|
@ -448,7 +462,7 @@ void AP_MotorsMulticopter::output_logic()
|
||||||
limit.throttle_upper = true;
|
limit.throttle_upper = true;
|
||||||
|
|
||||||
// set and increment ramp variables
|
// set and increment ramp variables
|
||||||
float spool_step = 1.0f/(AP_MOTORS_SPOOL_UP_TIME*_loop_rate);
|
float spool_step = 1.0f/(_spool_up_time*_loop_rate);
|
||||||
if (_spool_desired == DESIRED_SHUT_DOWN){
|
if (_spool_desired == DESIRED_SHUT_DOWN){
|
||||||
_spin_up_ratio -= spool_step;
|
_spin_up_ratio -= spool_step;
|
||||||
// constrain ramp value and update mode
|
// constrain ramp value and update mode
|
||||||
|
@ -491,7 +505,7 @@ void AP_MotorsMulticopter::output_logic()
|
||||||
|
|
||||||
// set and increment ramp variables
|
// set and increment ramp variables
|
||||||
_spin_up_ratio = 1.0f;
|
_spin_up_ratio = 1.0f;
|
||||||
_throttle_thrust_max += 1.0f/(AP_MOTORS_SPOOL_UP_TIME*_loop_rate);
|
_throttle_thrust_max += 1.0f/(_spool_up_time*_loop_rate);
|
||||||
|
|
||||||
// constrain ramp value and update mode
|
// constrain ramp value and update mode
|
||||||
if (_throttle_thrust_max >= MIN(get_throttle(), get_current_limit_max_throttle())) {
|
if (_throttle_thrust_max >= MIN(get_throttle(), get_current_limit_max_throttle())) {
|
||||||
|
@ -541,7 +555,7 @@ void AP_MotorsMulticopter::output_logic()
|
||||||
|
|
||||||
// set and increment ramp variables
|
// set and increment ramp variables
|
||||||
_spin_up_ratio = 1.0f;
|
_spin_up_ratio = 1.0f;
|
||||||
_throttle_thrust_max -= 1.0f/(AP_MOTORS_SPOOL_UP_TIME*_loop_rate);
|
_throttle_thrust_max -= 1.0f/(_spool_up_time*_loop_rate);
|
||||||
|
|
||||||
// constrain ramp value and update mode
|
// constrain ramp value and update mode
|
||||||
if (_throttle_thrust_max <= 0.0f){
|
if (_throttle_thrust_max <= 0.0f){
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
#define AP_MOTORS_BATT_VOLT_FILT_HZ 0.5f // battery voltage filtered at 0.5hz
|
#define AP_MOTORS_BATT_VOLT_FILT_HZ 0.5f // battery voltage filtered at 0.5hz
|
||||||
|
|
||||||
// spool definition
|
// spool definition
|
||||||
#define AP_MOTORS_SPOOL_UP_TIME 0.5f // time (in seconds) for throttle to increase from zero to min throttle, and min throttle to full throttle.
|
#define AP_MOTORS_SPOOL_UP_TIME_DEFAULT 0.5f // time (in seconds) for throttle to increase from zero to min throttle, and min throttle to full throttle.
|
||||||
|
|
||||||
/// @class AP_MotorsMulticopter
|
/// @class AP_MotorsMulticopter
|
||||||
class AP_MotorsMulticopter : public AP_Motors {
|
class AP_MotorsMulticopter : public AP_Motors {
|
||||||
|
@ -165,6 +165,9 @@ protected:
|
||||||
|
|
||||||
// Maximum lean angle of yaw servo in degrees. This is specific to tricopter
|
// Maximum lean angle of yaw servo in degrees. This is specific to tricopter
|
||||||
AP_Float _yaw_servo_angle_max_deg;
|
AP_Float _yaw_servo_angle_max_deg;
|
||||||
|
|
||||||
|
// time to spool motors to min throttle
|
||||||
|
AP_Float _spool_up_time;
|
||||||
|
|
||||||
// motor output variables
|
// motor output variables
|
||||||
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]; // true if motor is enabled
|
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]; // true if motor is enabled
|
||||||
|
|
Loading…
Reference in New Issue