mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_MotorsHeli_RSC: Split out rotor speed estimate into it's own function
This commit is contained in:
parent
064cc63512
commit
ed08e9d531
@ -65,9 +65,12 @@ void AP_MotorsHeli_RSC::output(uint8_t state)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// run speed ramp function to slew output smoothly, also updates estimated speed
|
// run speed ramp function to slew output smoothly
|
||||||
speed_ramp(_control_speed);
|
speed_ramp(_control_speed);
|
||||||
|
|
||||||
|
// update rotor speed estimate
|
||||||
|
update_speed_estimate();
|
||||||
|
|
||||||
// output to rsc servo
|
// output to rsc servo
|
||||||
write_rsc(_control_out);
|
write_rsc(_control_out);
|
||||||
}
|
}
|
||||||
@ -94,6 +97,12 @@ void AP_MotorsHeli_RSC::speed_ramp(int16_t speed_target)
|
|||||||
_control_out = speed_target;
|
_control_out = speed_target;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// update_speed_estimate - function to estimate speed
|
||||||
|
void AP_MotorsHeli_RSC::update_speed_estimate()
|
||||||
|
{
|
||||||
// ramp speed estimate towards control out
|
// ramp speed estimate towards control out
|
||||||
if (_estimated_speed < _control_out) {
|
if (_estimated_speed < _control_out) {
|
||||||
_estimated_speed += _runup_increment;
|
_estimated_speed += _runup_increment;
|
||||||
@ -107,8 +116,8 @@ void AP_MotorsHeli_RSC::speed_ramp(int16_t speed_target)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// set runup complete flag
|
// update run-up complete flag
|
||||||
if (!_runup_complete && speed_target > 0 && _estimated_speed >= speed_target) {
|
if (!_runup_complete && _control_out > _idle_speed && _estimated_speed >= _control_out) {
|
||||||
_runup_complete = true;
|
_runup_complete = true;
|
||||||
}
|
}
|
||||||
if (_runup_complete && _estimated_speed <= _critical_speed) {
|
if (_runup_complete && _estimated_speed <= _critical_speed) {
|
||||||
|
@ -81,6 +81,9 @@ private:
|
|||||||
// speed_ramp - ramps speed towards target, result put in _control_out
|
// speed_ramp - ramps speed towards target, result put in _control_out
|
||||||
void speed_ramp(int16_t rotor_target);
|
void speed_ramp(int16_t rotor_target);
|
||||||
|
|
||||||
|
// update_speed_estimate - function to estimate speed
|
||||||
|
void update_speed_estimate();
|
||||||
|
|
||||||
// write_rsc - outputs pwm onto output rsc channel. servo_out parameter is of the range 0 ~ 1000
|
// write_rsc - outputs pwm onto output rsc channel. servo_out parameter is of the range 0 ~ 1000
|
||||||
void write_rsc(int16_t servo_out);
|
void write_rsc(int16_t servo_out);
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user