MCLandDetector: fix low thrust detection in stabilized mode

HTE runs based on the position controller so, even if we whish to use
the estimate, it is only available in altitude and position modes.
Therefore, we need to always initialize the hoverThrottle using the hover
thrust parameter in case we fly in stabilized
This commit is contained in:
bresch
2020-04-22 13:30:40 +02:00
committed by Daniel Agar
parent be2bb4a479
commit d29344cb9c
2 changed files with 10 additions and 1 deletions

View File

@@ -118,8 +118,15 @@ void MulticopterLandDetector::_update_params()
param_get(_paramHandle.useHoverThrustEstimate, &use_hover_thrust_estimate);
_params.useHoverThrustEstimate = (use_hover_thrust_estimate == 1);
if (!_params.useHoverThrustEstimate) {
if (!_params.useHoverThrustEstimate || !_hover_thrust_initialized) {
param_get(_paramHandle.hoverThrottle, &_params.hoverThrottle);
// HTE runs based on the position controller so, even if we wish to use
// the estimate, it is only available in altitude and position modes.
// Therefore, we need to always initialize the hoverThrottle using the hover
// thrust parameter in case we fly in stabilized
// TODO: this can be removed once HTE runs in all modes
_hover_thrust_initialized = true;
}
}

View File

@@ -129,6 +129,8 @@ private:
vehicle_control_mode_s _vehicle_control_mode {};
vehicle_local_position_setpoint_s _vehicle_local_position_setpoint {};
bool _hover_thrust_initialized{false};
hrt_abstime _min_trust_start{0}; ///< timestamp when minimum trust was applied first
hrt_abstime _landed_time{0};