63 void update(
float rangefinder_alt_cm,
bool rangefinder_alt_valid);
93 void run_estimator(
float rangefinder_alt_m,
bool rangefinder_alt_valid);
struct AC_PrecLand::precland_state _backend_state
Vector3f correctedVehicleDeltaVelocityNED
AP_Buffer< inertial_data_frame_s, 8 > _inertial_history
bool get_target_position_cm(Vector2f &ret)
Vector2f _target_vel_rel_est_NE
Vector3f inertialNavVelocity
bool inertialNavVelocityValid
bool construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid)
AC_PrecLand(const AP_AHRS_NavEKF &ahrs)
bool get_target_velocity_relative_cms(Vector2f &ret)
Vector2f _target_pos_rel_est_NE
void run_output_prediction()
static const struct AP_Param::GroupInfo var_info[]
AC_PrecLand & operator=(const AC_PrecLand &)=delete
Vector3f _target_pos_rel_meas_NED
bool retrieve_los_meas(Vector3f &target_vec_unit_body)
bool get_target_position_relative_cm(Vector2f &ret)
void update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
uint32_t _last_backend_los_meas_ms
enum PrecLandBehaviour get_behaviour() const
Common definitions and utility routines for the ArduPilot libraries.
const AP_AHRS_NavEKF & _ahrs
Vector2f _target_vel_rel_out_NE
void handle_msg(mavlink_message_t *msg)
void run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid)
fifo (queue) buffer template class
Vector2f _target_pos_rel_out_NE
AC_PrecLand_Backend * _backend
uint32_t _outlier_reject_count
uint32_t last_update_ms() const