Browse Source

AC_PrecLand: replace AP_InertialNav by AHRS

master
Pierre Kancir 7 years ago committed by Randy Mackay
parent
commit
6fe0597399
  1. 23
      libraries/AC_PrecLand/AC_PrecLand.cpp
  2. 7
      libraries/AC_PrecLand/AC_PrecLand.h
  3. 1
      libraries/AC_PrecLand/AC_PrecLand_Backend.h

23
libraries/AC_PrecLand/AC_PrecLand.cpp

@ -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;
}

7
libraries/AC_PrecLand/AC_PrecLand.h

@ -2,11 +2,11 @@ @@ -2,11 +2,11 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_InertialNav/AP_InertialNav.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <stdint.h>
#include "PosVelEKF.h"
#include <AP_Buffer/AP_Buffer.h>
#include <AP_AHRS/AP_AHRS.h>
// declare backend classes
class AC_PrecLand_Backend;
@ -25,7 +25,7 @@ class AC_PrecLand @@ -25,7 +25,7 @@ class AC_PrecLand
friend class AC_PrecLand_SITL;
public:
AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav);
AC_PrecLand(const AP_AHRS_NavEKF& ahrs);
/* Do not allow copies */
AC_PrecLand(const AC_PrecLand &other) = delete;
@ -103,8 +103,7 @@ private: @@ -103,8 +103,7 @@ private:
void run_output_prediction();
// references to inertial nav and ahrs libraries
const AP_AHRS& _ahrs;
const AP_InertialNav& _inav;
const AP_AHRS_NavEKF& _ahrs;
// parameters
AP_Int8 _enabled; // enabled/disabled and behaviour

1
libraries/AC_PrecLand/AC_PrecLand_Backend.h

@ -3,7 +3,6 @@ @@ -3,7 +3,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AC_PID/AC_PID.h>
#include <AP_InertialNav/AP_InertialNav.h>
#include "AC_PrecLand.h"
class AC_PrecLand_Backend

Loading…
Cancel
Save