PX4 Firmware
PX4 Autopilot Software http://px4.io
landing_target_estimator::LandingTargetEstimator Class Reference

#include <LandingTargetEstimator.h>

Collaboration diagram for landing_target_estimator::LandingTargetEstimator:

Public Member Functions

 LandingTargetEstimator ()
 
virtual ~LandingTargetEstimator ()=default
 
void update ()
 

Protected Member Functions

void _update_topics ()
 
void _update_params ()
 

Protected Attributes

uORB::Publication< landing_target_pose_s_targetPosePub {ORB_ID(landing_target_pose)}
 
landing_target_pose_s _target_pose {}
 
uORB::Publication< landing_target_innovations_s_targetInnovationsPub {ORB_ID(landing_target_innovations)}
 
landing_target_innovations_s _target_innovations {}
 
uORB::Subscription _parameterSub {ORB_ID(parameter_update)}
 

Static Protected Attributes

static constexpr uint32_t landing_target_estimator_TIMEOUT_US = 2000000
 

Private Types

enum  TargetMode { TargetMode::Moving = 0, TargetMode::Stationary }
 

Private Member Functions

void _check_params (const bool force)
 
void _update_state ()
 

Private Attributes

struct {
   param_t   acc_unc
 
   param_t   meas_unc
 
   param_t   pos_unc_init
 
   param_t   vel_unc_init
 
   param_t   mode
 
   param_t   scale_x
 
   param_t   scale_y
 
_paramHandle
 Handles for parameters. More...
 
struct {
   float   acc_unc
 
   float   meas_unc
 
   float   pos_unc_init
 
   float   vel_unc_init
 
   TargetMode   mode
 
   float   scale_x
 
   float   scale_y
 
_params
 
uORB::Subscription _vehicleLocalPositionSub {ORB_ID(vehicle_local_position)}
 
uORB::Subscription _attitudeSub {ORB_ID(vehicle_attitude)}
 
uORB::Subscription _vehicle_acceleration_sub {ORB_ID(vehicle_acceleration)}
 
uORB::Subscription _irlockReportSub {ORB_ID(irlock_report)}
 
vehicle_local_position_s _vehicleLocalPosition {}
 
vehicle_attitude_s _vehicleAttitude {}
 
vehicle_acceleration_s _vehicle_acceleration {}
 
irlock_report_s _irlockReport {}
 
bool _vehicleLocalPosition_valid {false}
 
bool _vehicleAttitude_valid {false}
 
bool _vehicle_acceleration_valid {false}
 
bool _new_irlockReport {false}
 
bool _estimator_initialized {false}
 
bool _faulty {false}
 
matrix::Dcmf _R_att
 
matrix::Vector2f _rel_pos
 
KalmanFilter _kalman_filter_x
 
KalmanFilter _kalman_filter_y
 
hrt_abstime _last_predict {0}
 
hrt_abstime _last_update {0}
 

Detailed Description

Definition at line 66 of file LandingTargetEstimator.h.

Member Enumeration Documentation

◆ TargetMode

Enumerator
Moving 
Stationary 

Definition at line 103 of file LandingTargetEstimator.h.

Constructor & Destructor Documentation

◆ LandingTargetEstimator()

landing_target_estimator::LandingTargetEstimator::LandingTargetEstimator ( )

Definition at line 54 of file LandingTargetEstimator.cpp.

References _check_params(), _paramHandle, and param_find().

Here is the call graph for this function:

◆ ~LandingTargetEstimator()

virtual landing_target_estimator::LandingTargetEstimator::~LandingTargetEstimator ( )
virtualdefault

Member Function Documentation

◆ _check_params()

void landing_target_estimator::LandingTargetEstimator::_check_params ( const bool  force)
private

Definition at line 226 of file LandingTargetEstimator.cpp.

References _parameterSub, _update_params(), uORB::Subscription::copy(), and uORB::Subscription::updated().

Referenced by LandingTargetEstimator(), and update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_params()

void landing_target_estimator::LandingTargetEstimator::_update_params ( )
protected

Definition at line 249 of file LandingTargetEstimator.cpp.

References _paramHandle, _params, and param_get().

Referenced by _check_params().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_state()

void landing_target_estimator::LandingTargetEstimator::_update_state ( )
private

◆ _update_topics()

void landing_target_estimator::LandingTargetEstimator::_update_topics ( )
protected

Definition at line 240 of file LandingTargetEstimator.cpp.

References _attitudeSub, _irlockReport, _irlockReportSub, _new_irlockReport, _vehicle_acceleration, _vehicle_acceleration_sub, _vehicle_acceleration_valid, _vehicleAttitude, _vehicleAttitude_valid, _vehicleLocalPosition, _vehicleLocalPosition_valid, _vehicleLocalPositionSub, and uORB::Subscription::update().

Referenced by update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update()

void landing_target_estimator::LandingTargetEstimator::update ( )

Definition at line 67 of file LandingTargetEstimator.cpp.

References _check_params(), _estimator_initialized, _faulty, _irlockReport, _kalman_filter_x, _kalman_filter_y, _last_predict, _last_update, _new_irlockReport, _params, _R_att, _rel_pos, _target_innovations, _target_pose, _targetInnovationsPub, _targetPosePub, _update_topics(), _vehicle_acceleration, _vehicle_acceleration_valid, _vehicleAttitude, _vehicleAttitude_valid, _vehicleLocalPosition, _vehicleLocalPosition_valid, landing_target_pose_s::abs_pos_valid, landing_target_pose_s::cov_vx_rel, landing_target_pose_s::cov_vy_rel, landing_target_pose_s::cov_x_rel, landing_target_pose_s::cov_y_rel, vehicle_local_position_s::dist_bottom, vehicle_local_position_s::dist_bottom_valid, dt, f(), landing_target_estimator::KalmanFilter::getCovariance(), landing_target_estimator::KalmanFilter::getInnovations(), landing_target_estimator::KalmanFilter::getState(), hrt_absolute_time(), landing_target_estimator::KalmanFilter::init(), landing_target_innovations_s::innov_cov_x, landing_target_innovations_s::innov_cov_y, landing_target_innovations_s::innov_x, landing_target_innovations_s::innov_y, landing_target_pose_s::is_static, landing_target_estimator_TIMEOUT_US, irlock_report_s::pos_x, irlock_report_s::pos_y, landing_target_estimator::KalmanFilter::predict(), uORB::Publication< T >::publish(), vehicle_attitude_s::q, landing_target_pose_s::rel_pos_valid, landing_target_pose_s::rel_vel_valid, SEC2USEC, Stationary, landing_target_pose_s::timestamp, landing_target_innovations_s::timestamp, irlock_report_s::timestamp, landing_target_estimator::KalmanFilter::update(), vehicle_local_position_s::v_xy_valid, vehicle_local_position_s::vx, landing_target_pose_s::vx_rel, vehicle_local_position_s::vy, landing_target_pose_s::vy_rel, vehicle_local_position_s::x, landing_target_pose_s::x_abs, landing_target_pose_s::x_rel, vehicle_local_position_s::xy_valid, vehicle_acceleration_s::xyz, vehicle_local_position_s::y, landing_target_pose_s::y_abs, landing_target_pose_s::y_rel, vehicle_local_position_s::z, landing_target_pose_s::z_abs, landing_target_pose_s::z_rel, and matrix::Matrix< Type, M, N >::zero().

Referenced by landing_target_estimator::landing_target_estimator_thread_main().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _attitudeSub

uORB::Subscription landing_target_estimator::LandingTargetEstimator::_attitudeSub {ORB_ID(vehicle_attitude)}
private

Definition at line 132 of file LandingTargetEstimator.h.

Referenced by _update_topics().

◆ _estimator_initialized

bool landing_target_estimator::LandingTargetEstimator::_estimator_initialized {false}
private

Definition at line 146 of file LandingTargetEstimator.h.

Referenced by update().

◆ _faulty

bool landing_target_estimator::LandingTargetEstimator::_faulty {false}
private

Definition at line 148 of file LandingTargetEstimator.h.

Referenced by update().

◆ _irlockReport

irlock_report_s landing_target_estimator::LandingTargetEstimator::_irlockReport {}
private

Definition at line 139 of file LandingTargetEstimator.h.

Referenced by _update_topics(), and update().

◆ _irlockReportSub

uORB::Subscription landing_target_estimator::LandingTargetEstimator::_irlockReportSub {ORB_ID(irlock_report)}
private

Definition at line 134 of file LandingTargetEstimator.h.

Referenced by _update_topics().

◆ _kalman_filter_x

KalmanFilter landing_target_estimator::LandingTargetEstimator::_kalman_filter_x
private

Definition at line 152 of file LandingTargetEstimator.h.

Referenced by update().

◆ _kalman_filter_y

KalmanFilter landing_target_estimator::LandingTargetEstimator::_kalman_filter_y
private

Definition at line 153 of file LandingTargetEstimator.h.

Referenced by update().

◆ _last_predict

hrt_abstime landing_target_estimator::LandingTargetEstimator::_last_predict {0}
private

Definition at line 154 of file LandingTargetEstimator.h.

Referenced by update().

◆ _last_update

hrt_abstime landing_target_estimator::LandingTargetEstimator::_last_update {0}
private

Definition at line 155 of file LandingTargetEstimator.h.

Referenced by update().

◆ _new_irlockReport

bool landing_target_estimator::LandingTargetEstimator::_new_irlockReport {false}
private

Definition at line 145 of file LandingTargetEstimator.h.

Referenced by _update_topics(), and update().

◆ _parameterSub

uORB::Subscription landing_target_estimator::LandingTargetEstimator::_parameterSub {ORB_ID(parameter_update)}
protected

Definition at line 99 of file LandingTargetEstimator.h.

Referenced by _check_params().

◆ _paramHandle

struct { ... } landing_target_estimator::LandingTargetEstimator::_paramHandle

Handles for parameters.

Referenced by _update_params(), and LandingTargetEstimator().

◆ _params

struct { ... } landing_target_estimator::LandingTargetEstimator::_params

Referenced by _update_params(), and update().

◆ _R_att

matrix::Dcmf landing_target_estimator::LandingTargetEstimator::_R_att
private

Definition at line 150 of file LandingTargetEstimator.h.

Referenced by update().

◆ _rel_pos

matrix::Vector2f landing_target_estimator::LandingTargetEstimator::_rel_pos
private

Definition at line 151 of file LandingTargetEstimator.h.

Referenced by update().

◆ _target_innovations

landing_target_innovations_s landing_target_estimator::LandingTargetEstimator::_target_innovations {}
protected

Definition at line 97 of file LandingTargetEstimator.h.

Referenced by update().

◆ _target_pose

landing_target_pose_s landing_target_estimator::LandingTargetEstimator::_target_pose {}
protected

Definition at line 94 of file LandingTargetEstimator.h.

Referenced by update().

◆ _targetInnovationsPub

uORB::Publication<landing_target_innovations_s> landing_target_estimator::LandingTargetEstimator::_targetInnovationsPub {ORB_ID(landing_target_innovations)}
protected

Definition at line 96 of file LandingTargetEstimator.h.

Referenced by update().

◆ _targetPosePub

uORB::Publication<landing_target_pose_s> landing_target_estimator::LandingTargetEstimator::_targetPosePub {ORB_ID(landing_target_pose)}
protected

Definition at line 93 of file LandingTargetEstimator.h.

Referenced by update().

◆ _vehicle_acceleration

vehicle_acceleration_s landing_target_estimator::LandingTargetEstimator::_vehicle_acceleration {}
private

Definition at line 138 of file LandingTargetEstimator.h.

Referenced by _update_topics(), and update().

◆ _vehicle_acceleration_sub

uORB::Subscription landing_target_estimator::LandingTargetEstimator::_vehicle_acceleration_sub {ORB_ID(vehicle_acceleration)}
private

Definition at line 133 of file LandingTargetEstimator.h.

Referenced by _update_topics().

◆ _vehicle_acceleration_valid

bool landing_target_estimator::LandingTargetEstimator::_vehicle_acceleration_valid {false}
private

Definition at line 144 of file LandingTargetEstimator.h.

Referenced by _update_topics(), and update().

◆ _vehicleAttitude

vehicle_attitude_s landing_target_estimator::LandingTargetEstimator::_vehicleAttitude {}
private

Definition at line 137 of file LandingTargetEstimator.h.

Referenced by _update_topics(), and update().

◆ _vehicleAttitude_valid

bool landing_target_estimator::LandingTargetEstimator::_vehicleAttitude_valid {false}
private

Definition at line 143 of file LandingTargetEstimator.h.

Referenced by _update_topics(), and update().

◆ _vehicleLocalPosition

vehicle_local_position_s landing_target_estimator::LandingTargetEstimator::_vehicleLocalPosition {}
private

Definition at line 136 of file LandingTargetEstimator.h.

Referenced by _update_topics(), and update().

◆ _vehicleLocalPosition_valid

bool landing_target_estimator::LandingTargetEstimator::_vehicleLocalPosition_valid {false}
private

Definition at line 142 of file LandingTargetEstimator.h.

Referenced by _update_topics(), and update().

◆ _vehicleLocalPositionSub

uORB::Subscription landing_target_estimator::LandingTargetEstimator::_vehicleLocalPositionSub {ORB_ID(vehicle_local_position)}
private

Definition at line 131 of file LandingTargetEstimator.h.

Referenced by _update_topics().

◆ acc_unc [1/2]

param_t landing_target_estimator::LandingTargetEstimator::acc_unc

Definition at line 112 of file LandingTargetEstimator.h.

◆ acc_unc [2/2]

float landing_target_estimator::LandingTargetEstimator::acc_unc

Definition at line 122 of file LandingTargetEstimator.h.

◆ landing_target_estimator_TIMEOUT_US

constexpr uint32_t landing_target_estimator::LandingTargetEstimator::landing_target_estimator_TIMEOUT_US = 2000000
staticprotected

Definition at line 91 of file LandingTargetEstimator.h.

Referenced by update().

◆ meas_unc [1/2]

param_t landing_target_estimator::LandingTargetEstimator::meas_unc

Definition at line 113 of file LandingTargetEstimator.h.

◆ meas_unc [2/2]

float landing_target_estimator::LandingTargetEstimator::meas_unc

Definition at line 123 of file LandingTargetEstimator.h.

◆ mode [1/2]

param_t landing_target_estimator::LandingTargetEstimator::mode

Definition at line 116 of file LandingTargetEstimator.h.

◆ mode [2/2]

TargetMode landing_target_estimator::LandingTargetEstimator::mode

Definition at line 126 of file LandingTargetEstimator.h.

◆ pos_unc_init [1/2]

param_t landing_target_estimator::LandingTargetEstimator::pos_unc_init

Definition at line 114 of file LandingTargetEstimator.h.

◆ pos_unc_init [2/2]

float landing_target_estimator::LandingTargetEstimator::pos_unc_init

Definition at line 124 of file LandingTargetEstimator.h.

◆ scale_x [1/2]

param_t landing_target_estimator::LandingTargetEstimator::scale_x

Definition at line 117 of file LandingTargetEstimator.h.

◆ scale_x [2/2]

float landing_target_estimator::LandingTargetEstimator::scale_x

Definition at line 127 of file LandingTargetEstimator.h.

◆ scale_y [1/2]

param_t landing_target_estimator::LandingTargetEstimator::scale_y

Definition at line 118 of file LandingTargetEstimator.h.

◆ scale_y [2/2]

float landing_target_estimator::LandingTargetEstimator::scale_y

Definition at line 128 of file LandingTargetEstimator.h.

◆ vel_unc_init [1/2]

param_t landing_target_estimator::LandingTargetEstimator::vel_unc_init

Definition at line 115 of file LandingTargetEstimator.h.

◆ vel_unc_init [2/2]

float landing_target_estimator::LandingTargetEstimator::vel_unc_init

Definition at line 125 of file LandingTargetEstimator.h.


The documentation for this class was generated from the following files: