103 _target_acquired(false),
104 _last_backend_los_meas_ms(0),
140 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 170 curr_vel.
z = -curr_vel.
z;
276 const float& dt = inertial_data_delayed.
dt;
336 cos_yaw_align, -sin_yaw_align, 0,
337 sin_yaw_align, cos_yaw_align, 0,
341 target_vec_unit_body = Rz*target_vec_unit_body;
354 Vector3f target_vec_unit_ned = inertial_data_delayed.
Tbn * target_vec_unit_body;
355 bool target_vec_valid = target_vec_unit_ned.
z > 0.0f;
357 if (target_vec_valid && alt_valid) {
361 alt = dist * target_vec_unit_ned.
z;
363 alt =
MAX(rangefinder_alt_m, 0.0
f);
364 dist = alt / target_vec_unit_ned.
z;
397 Vector3f imu_pos_ned = Tbn * accel_body_offset;
struct AC_PrecLand::precland_state _backend_state
Vector3f correctedVehicleDeltaVelocityNED
Vector3< float > Vector3f
#define AP_PARAM_FLAG_ENABLE
AP_Buffer< inertial_data_frame_s, 8 > _inertial_history
bool get_target_position_cm(Vector2f &ret)
virtual bool have_los_meas()=0
const Vector3f & get_gyro(void) const override
virtual void handle_msg(mavlink_message_t *msg)
Vector2f _target_vel_rel_est_NE
bool get_filter_status(nav_filter_status &status) const
Vector3f inertialNavVelocity
bool inertialNavVelocityValid
bool construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid)
#define AP_GROUPINFO(name, idx, clazz, element, def)
void init(float pos, float posVar, float vel, float velVar)
virtual float distance_to_target()
virtual uint32_t los_meas_time_ms()=0
AC_PrecLand(const AP_AHRS_NavEKF &ahrs)
bool get_target_velocity_relative_cms(Vector2f &ret)
Vector2f _target_pos_rel_est_NE
Matrix3< float > Matrix3f
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
void fusePos(float pos, float posVar)
void run_output_prediction()
void predict(float dt, float dVel, float dVelNoise)
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
static const struct AP_Param::GroupInfo var_info[]
Vector3f _target_pos_rel_meas_NED
virtual bool get_los_body(Vector3f &dir_body)=0
bool retrieve_los_meas(Vector3f &target_vec_unit_body)
void getCorrectedDeltaVelocityNED(Vector3f &ret, float &dt) const override
bool get_target_position_relative_cm(Vector2f &ret)
uint8_t get_primary_accel_index(void) const override
void update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
bool get_relative_position_NE_origin(Vector2f &posNE) const override
const Vector3f & get_imu_pos_offset(uint8_t instance) const
friend class AC_PrecLand_SITL
uint32_t _last_backend_los_meas_ms
friend class AC_PrecLand_Companion
struct nav_filter_status::@138 flags
friend class AC_PrecLand_IRLock
const AP_AHRS_NavEKF & _ahrs
Vector2f _target_vel_rel_out_NE
static constexpr float radians(float deg)
void handle_msg(mavlink_message_t *msg)
const Matrix3f & get_rotation_body_to_ned(void) const override
void run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid)
AP_InertialSensor & ins()
friend class AC_PrecLand_SITL_Gazebo
bool get_velocity_NED(Vector3f &vec) const override
float getPosNIS(float pos, float posVar)
Vector2f _target_pos_rel_out_NE
AC_PrecLand_Backend * _backend
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
uint32_t _outlier_reject_count