mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_MotorsMulticopter: add HOVER_LEARN option to learn but not save
This commit is contained in:
parent
23f8227e36
commit
e185bab775
@ -134,9 +134,9 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
|||||||
// @Param: HOVER_LEARN
|
// @Param: HOVER_LEARN
|
||||||
// @DisplayName: Hover Value Learning
|
// @DisplayName: Hover Value Learning
|
||||||
// @Description: Enable/Disable automatic learning of hover throttle
|
// @Description: Enable/Disable automatic learning of hover throttle
|
||||||
// @Values: 0:Disabled, 1:Enabled
|
// @Values: 0:Disabled, 1:Learn, 2:LearnAndSave
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("HOVER_LEARN", 22, AP_MotorsMulticopter, _throttle_hover_learn, 1),
|
AP_GROUPINFO("HOVER_LEARN", 22, AP_MotorsMulticopter, _throttle_hover_learn, HOVER_LEARN_AND_SAVE),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
@ -374,7 +374,7 @@ void AP_MotorsMulticopter::set_throttle_range(int16_t radio_min, int16_t radio_m
|
|||||||
// update the throttle input filter. should be called at 100hz
|
// update the throttle input filter. should be called at 100hz
|
||||||
void AP_MotorsMulticopter::update_throttle_hover(float dt)
|
void AP_MotorsMulticopter::update_throttle_hover(float dt)
|
||||||
{
|
{
|
||||||
if (_throttle_hover_learn > 0) {
|
if (_throttle_hover_learn != HOVER_LEARN_DISABLED) {
|
||||||
_throttle_hover = _throttle_hover + (dt/(dt+AP_MOTORS_THST_HOVER_TC))*(_throttle_in-_throttle_hover);
|
_throttle_hover = _throttle_hover + (dt/(dt+AP_MOTORS_THST_HOVER_TC))*(_throttle_in-_throttle_hover);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -570,7 +570,7 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask)
|
|||||||
void AP_MotorsMulticopter::save_params_on_disarm()
|
void AP_MotorsMulticopter::save_params_on_disarm()
|
||||||
{
|
{
|
||||||
// save hover throttle
|
// save hover throttle
|
||||||
if (_throttle_hover_learn > 0) {
|
if (_throttle_hover_learn == HOVER_LEARN_AND_SAVE) {
|
||||||
_throttle_hover.save();
|
_throttle_hover.save();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -140,6 +140,13 @@ protected:
|
|||||||
// save parameters as part of disarming
|
// save parameters as part of disarming
|
||||||
void save_params_on_disarm();
|
void save_params_on_disarm();
|
||||||
|
|
||||||
|
// enum values for HOVER_LEARN parameter
|
||||||
|
enum HoverLearn {
|
||||||
|
HOVER_LEARN_DISABLED = 0,
|
||||||
|
HOVER_LEARN_ONLY = 1,
|
||||||
|
HOVER_LEARN_AND_SAVE = 2
|
||||||
|
};
|
||||||
|
|
||||||
// parameters
|
// parameters
|
||||||
AP_Int16 _yaw_headroom; // yaw control is given at least this pwm range
|
AP_Int16 _yaw_headroom; // yaw control is given at least this pwm range
|
||||||
AP_Float _thrust_curve_expo; // curve used to linearize pwm to thrust conversion. set to 0 for linear and 1 for second order approximation
|
AP_Float _thrust_curve_expo; // curve used to linearize pwm to thrust conversion. set to 0 for linear and 1 for second order approximation
|
||||||
|
Loading…
Reference in New Issue
Block a user