|
|
|
@ -97,9 +97,8 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
@@ -97,9 +97,8 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
|
|
|
|
|
// Note that the Vector/Matrix constructors already implicitly zero
|
|
|
|
|
// their values.
|
|
|
|
|
//
|
|
|
|
|
AC_PrecLand::AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav) : |
|
|
|
|
AC_PrecLand::AC_PrecLand(const AP_AHRS_NavEKF& ahrs) : |
|
|
|
|
_ahrs(ahrs), |
|
|
|
|
_inav(inav), |
|
|
|
|
_last_update_ms(0), |
|
|
|
|
_target_acquired(false), |
|
|
|
|
_last_backend_los_meas_ms(0), |
|
|
|
@ -161,8 +160,16 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
@@ -161,8 +160,16 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
|
|
|
|
|
struct inertial_data_frame_s inertial_data_newest; |
|
|
|
|
_ahrs.getCorrectedDeltaVelocityNED(inertial_data_newest.correctedVehicleDeltaVelocityNED, inertial_data_newest.dt); |
|
|
|
|
inertial_data_newest.Tbn = _ahrs.get_rotation_body_to_ned(); |
|
|
|
|
inertial_data_newest.inertialNavVelocity = _inav.get_velocity()*0.01f; |
|
|
|
|
inertial_data_newest.inertialNavVelocityValid = _inav.get_filter_status().flags.horiz_vel; |
|
|
|
|
Vector3f curr_vel; |
|
|
|
|
nav_filter_status status; |
|
|
|
|
if (!_ahrs.get_velocity_NED(curr_vel) || !_ahrs.get_filter_status(status)) { |
|
|
|
|
inertial_data_newest.inertialNavVelocityValid = false; |
|
|
|
|
} else { |
|
|
|
|
inertial_data_newest.inertialNavVelocityValid = status.flags.horiz_vel; |
|
|
|
|
} |
|
|
|
|
curr_vel.z = -curr_vel.z; // NED to NEU
|
|
|
|
|
inertial_data_newest.inertialNavVelocity = curr_vel; |
|
|
|
|
|
|
|
|
|
_inertial_history.push_back(inertial_data_newest); |
|
|
|
|
|
|
|
|
|
// update estimator of target position
|
|
|
|
@ -183,8 +190,12 @@ bool AC_PrecLand::get_target_position_cm(Vector2f& ret)
@@ -183,8 +190,12 @@ bool AC_PrecLand::get_target_position_cm(Vector2f& ret)
|
|
|
|
|
if (!target_acquired()) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
ret.x = _target_pos_rel_out_NE.x*100.0f + _inav.get_position().x; |
|
|
|
|
ret.y = _target_pos_rel_out_NE.y*100.0f + _inav.get_position().y; |
|
|
|
|
Vector2f curr_pos; |
|
|
|
|
if (!_ahrs.get_relative_position_NE_origin(curr_pos)) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
ret.x = (_target_pos_rel_out_NE.x + curr_pos.x) * 100.0f; // m to cm
|
|
|
|
|
ret.y = (_target_pos_rel_out_NE.y + curr_pos.y) * 100.0f; // m to cm
|
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|