@ -41,10 +41,13 @@
@@ -41,10 +41,13 @@
# include <mathlib/mathlib.h>
using namespace time_literals ;
MulticopterHoverThrustEstimator : : MulticopterHoverThrustEstimator ( ) :
ModuleParams ( nullptr ) ,
WorkItem ( MODULE_NAME , px4 : : wq_configurations : : lp_default )
WorkItem ( MODULE_NAME , px4 : : wq_configurations : : nav_and_controllers )
{
_valid_hysteresis . set_hysteresis_time_from ( false , 2 _s ) ;
updateParams ( ) ;
reset ( ) ;
}
@ -93,6 +96,11 @@ void MulticopterHoverThrustEstimator::Run()
@@ -93,6 +96,11 @@ void MulticopterHoverThrustEstimator::Run()
return ;
}
// new local position estimate and setpoint needed every iteration
if ( ! _vehicle_local_pos_sub . updated ( ) | | ! _vehicle_local_position_setpoint_sub . updated ( ) ) {
return ;
}
// check for parameter updates
if ( _parameter_update_sub . updated ( ) ) {
// clear update
@ -105,73 +113,112 @@ void MulticopterHoverThrustEstimator::Run()
@@ -105,73 +113,112 @@ void MulticopterHoverThrustEstimator::Run()
perf_begin ( _cycle_perf ) ;
if ( _vehicle_land_detected_sub . updated ( ) ) {
vehicle_land_detected_s vehicle_land_detected ;
vehicle_status_s vehicle_status ;
vehicle_local_position_s local_pos ;
if ( _vehicle_land_detected_sub . update ( & vehicle_land_detected ) ) {
if ( _vehicle_land_detected_sub . copy ( & vehicle_land_detected ) ) {
_landed = vehicle_land_detected . landed ;
}
}
if ( _vehicle_status_sub . updated ( ) ) {
vehicle_status_s vehicle_status ;
if ( _vehicle_status_sub . update ( & vehicle_status ) ) {
if ( _vehicle_status_sub . copy ( & vehicle_status ) ) {
_armed = ( vehicle_status . arming_state = = vehicle_status_s : : ARMING_STATE_ARMED ) ;
}
}
// always copy latest position estimate
vehicle_local_position_s local_pos { } ;
if ( _vehicle_local_pos_sub . update ( & local_pos ) ) {
if ( _vehicle_local_pos_sub . copy ( & local_pos ) ) {
// This is only necessary because the landed
// flag of the land detector does not guarantee that
// the vehicle does not touch the ground anymore
// TODO: improve the landed flag
if ( local_pos . dist_bottom_valid ) {
_in_air = local_pos . dist_bottom > 1.f ;
}
}
ZeroOrderHoverThrustEkf : : status status { } ;
if ( _armed & & ! _landed & & _in_air ) {
vehicle_local_position_setpoint_s local_pos_sp ;
if ( _vehicle_local_position_setpoint_sub . update ( & local_pos_sp ) ) {
const float dt = ( local_pos . timestamp - _timestamp_last ) * 1e-6 f ;
_timestamp_last = local_pos . timestamp ;
const hrt_abstime now = hrt_absolute_time ( ) ;
const float dt = math : : constrain ( ( now - _timestamp_last ) / 1e6 f , 0.002f , 0.2f ) ;
if ( _armed & & ! _landed & & ( dt > 0.001f ) & & ( dt < 1.f ) & & PX4_ISFINITE ( local_pos . az ) ) {
_hover_thrust_ekf . predict ( dt ) ;
if ( PX4_ISFINITE ( local_pos . az ) & & PX4_ISFINITE ( local_pos_sp . thrust [ 2 ] ) ) {
vehicle_local_position_setpoint_s local_pos_sp ;
if ( _vehicle_local_position_setpoint_sub . update ( & local_pos_sp ) ) {
if ( PX4_ISFINITE ( local_pos_sp . thrust [ 2 ] ) ) {
// Inform the hover thrust estimator about the measured vertical
// acceleration (positive acceleration is up) and the current thrust (positive thrust is up)
ZeroOrderHoverThrustEkf : : status status ;
_hover_thrust_ekf . fuseAccZ ( - local_pos . az , - local_pos_sp . thrust [ 2 ] , status ) ;
const bool valid = _in_air & & ( status . hover_thrust_var < 0.001f ) & & ( status . innov_test_ratio < 1.f ) ;
_valid_hysteresis . set_state_and_update ( valid , local_pos . timestamp ) ;
_valid = _valid_hysteresis . get_state ( ) ;
publishStatus ( local_pos . timestamp , status ) ;
}
}
} else {
_valid_hysteresis . set_state_and_update ( false , hrt_absolute_time ( ) ) ;
if ( ! _armed ) {
reset ( ) ;
}
status . hover_thrust = _hover_thrust_ekf . getHoverThrustEstimate ( ) ;
status . hover_thrust_var = _hover_thrust_ekf . getHoverThrustEstimateVar ( ) ;
status . accel_noise_var = _hover_thrust_ekf . getAccelNoiseVar ( ) ;
status . innov = NAN ;
status . innov_var = NAN ;
status . innov_test_ratio = NAN ;
}
if ( _valid ) {
// only publish a single message to invalidate
publishInvalidStatus ( ) ;
publishStatus ( status ) ;
_valid = false ;
}
}
perf_end ( _cycle_perf ) ;
}
void MulticopterHoverThrustEstimator : : publishStatus ( ZeroOrderHoverThrustEkf : : status & status )
void MulticopterHoverThrustEstimator : : publishStatus ( const hrt_abstime & timestamp_sample ,
const ZeroOrderHoverThrustEkf : : status & status )
{
hover_thrust_estimate_s status_msg { } ;
hover_thrust_estimate_s status_msg ;
status_msg . timestamp_sample = timestamp_sample ;
status_msg . hover_thrust = status . hover_thrust ;
status_msg . hover_thrust_var = status . hover_thrust_var ;
status_msg . accel_innov = status . innov ;
status_msg . accel_innov_var = status . innov_var ;
status_msg . accel_innov_test_ratio = status . innov_test_ratio ;
status_msg . accel_noise_var = status . accel_noise_var ;
status_msg . valid = _valid ;
status_msg . timestamp = hrt_absolute_time ( ) ;
_hover_thrust_ekf_pub . publish ( status_msg ) ;
}
void MulticopterHoverThrustEstimator : : publishInvalidStatus ( )
{
hover_thrust_estimate_s status_msg { } ;
status_msg . hover_thrust = NAN ;
status_msg . hover_thrust_var = NAN ;
status_msg . accel_innov = NAN ;
status_msg . accel_innov_var = NAN ;
status_msg . accel_innov_test_ratio = NAN ;
status_msg . accel_noise_var = NAN ;
status_msg . timestamp = hrt_absolute_time ( ) ;
_hover_thrust_ekf_pub . publish ( status_msg ) ;
}