#include <LandingTargetEstimator.h>
Definition at line 66 of file LandingTargetEstimator.h.
◆ TargetMode
◆ LandingTargetEstimator()
landing_target_estimator::LandingTargetEstimator::LandingTargetEstimator |
( |
| ) |
|
◆ ~LandingTargetEstimator()
virtual landing_target_estimator::LandingTargetEstimator::~LandingTargetEstimator |
( |
| ) |
|
|
virtualdefault |
◆ _check_params()
void landing_target_estimator::LandingTargetEstimator::_check_params |
( |
const bool |
force | ) |
|
|
private |
◆ _update_params()
void landing_target_estimator::LandingTargetEstimator::_update_params |
( |
| ) |
|
|
protected |
◆ _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().
◆ 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().
◆ _attitudeSub
◆ _estimator_initialized
bool landing_target_estimator::LandingTargetEstimator::_estimator_initialized {false} |
|
private |
◆ _faulty
bool landing_target_estimator::LandingTargetEstimator::_faulty {false} |
|
private |
◆ _irlockReport
irlock_report_s landing_target_estimator::LandingTargetEstimator::_irlockReport {} |
|
private |
◆ _irlockReportSub
◆ _kalman_filter_x
KalmanFilter landing_target_estimator::LandingTargetEstimator::_kalman_filter_x |
|
private |
◆ _kalman_filter_y
KalmanFilter landing_target_estimator::LandingTargetEstimator::_kalman_filter_y |
|
private |
◆ _last_predict
hrt_abstime landing_target_estimator::LandingTargetEstimator::_last_predict {0} |
|
private |
◆ _last_update
hrt_abstime landing_target_estimator::LandingTargetEstimator::_last_update {0} |
|
private |
◆ _new_irlockReport
bool landing_target_estimator::LandingTargetEstimator::_new_irlockReport {false} |
|
private |
◆ _parameterSub
◆ _paramHandle
struct { ... } landing_target_estimator::LandingTargetEstimator::_paramHandle |
◆ _params
struct { ... } landing_target_estimator::LandingTargetEstimator::_params |
◆ _R_att
matrix::Dcmf landing_target_estimator::LandingTargetEstimator::_R_att |
|
private |
◆ _rel_pos
◆ _target_innovations
◆ _target_pose
◆ _targetInnovationsPub
◆ _targetPosePub
◆ _vehicle_acceleration
◆ _vehicle_acceleration_sub
uORB::Subscription landing_target_estimator::LandingTargetEstimator::_vehicle_acceleration_sub {ORB_ID(vehicle_acceleration)} |
|
private |
◆ _vehicle_acceleration_valid
bool landing_target_estimator::LandingTargetEstimator::_vehicle_acceleration_valid {false} |
|
private |
◆ _vehicleAttitude
◆ _vehicleAttitude_valid
bool landing_target_estimator::LandingTargetEstimator::_vehicleAttitude_valid {false} |
|
private |
◆ _vehicleLocalPosition
◆ _vehicleLocalPosition_valid
bool landing_target_estimator::LandingTargetEstimator::_vehicleLocalPosition_valid {false} |
|
private |
◆ _vehicleLocalPositionSub
uORB::Subscription landing_target_estimator::LandingTargetEstimator::_vehicleLocalPositionSub {ORB_ID(vehicle_local_position)} |
|
private |
◆ acc_unc [1/2]
param_t landing_target_estimator::LandingTargetEstimator::acc_unc |
◆ acc_unc [2/2]
float landing_target_estimator::LandingTargetEstimator::acc_unc |
◆ landing_target_estimator_TIMEOUT_US
constexpr uint32_t landing_target_estimator::LandingTargetEstimator::landing_target_estimator_TIMEOUT_US = 2000000 |
|
staticprotected |
◆ meas_unc [1/2]
param_t landing_target_estimator::LandingTargetEstimator::meas_unc |
◆ meas_unc [2/2]
float landing_target_estimator::LandingTargetEstimator::meas_unc |
◆ mode [1/2]
param_t landing_target_estimator::LandingTargetEstimator::mode |
◆ mode [2/2]
TargetMode landing_target_estimator::LandingTargetEstimator::mode |
◆ pos_unc_init [1/2]
param_t landing_target_estimator::LandingTargetEstimator::pos_unc_init |
◆ pos_unc_init [2/2]
float landing_target_estimator::LandingTargetEstimator::pos_unc_init |
◆ scale_x [1/2]
param_t landing_target_estimator::LandingTargetEstimator::scale_x |
◆ scale_x [2/2]
float landing_target_estimator::LandingTargetEstimator::scale_x |
◆ scale_y [1/2]
param_t landing_target_estimator::LandingTargetEstimator::scale_y |
◆ scale_y [2/2]
float landing_target_estimator::LandingTargetEstimator::scale_y |
◆ vel_unc_init [1/2]
param_t landing_target_estimator::LandingTargetEstimator::vel_unc_init |
◆ vel_unc_init [2/2]
float landing_target_estimator::LandingTargetEstimator::vel_unc_init |
The documentation for this class was generated from the following files: