ArduCopter: Add EKF3 and remove EKF1
This commit is contained in:
parent
33943de4a0
commit
c3b9dbf5c8
@ -46,8 +46,8 @@
|
||||
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_NavEKF/AP_NavEKF.h>
|
||||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||
#include <AP_NavEKF3/AP_NavEKF3.h>
|
||||
#include <AP_Mission/AP_Mission.h> // Mission command library
|
||||
#include <AC_PID/AC_PID.h> // PID library
|
||||
#include <AC_PID/AC_PI_2D.h> // PID library (2-axis)
|
||||
@ -202,9 +202,9 @@ private:
|
||||
AP_RPM rpm_sensor;
|
||||
|
||||
// Inertial Navigation EKF
|
||||
NavEKF EKF{&ahrs, barometer, rangefinder};
|
||||
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, gps, rangefinder, EKF, EKF2, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
||||
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, gps, rangefinder, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
SITL::SITL sitl;
|
||||
|
@ -378,9 +378,9 @@ void Copter::Log_Write_Attitude()
|
||||
DataFlash.Log_Write_Attitude(ahrs, targets);
|
||||
|
||||
#if OPTFLOW == ENABLED
|
||||
DataFlash.Log_Write_EKF2(ahrs,optflow.enabled());
|
||||
DataFlash.Log_Write_EKF(ahrs,optflow.enabled());
|
||||
#else
|
||||
DataFlash.Log_Write_EKF2(ahrs,false);
|
||||
DataFlash.Log_Write_EKF(ahrs,false);
|
||||
#endif
|
||||
DataFlash.Log_Write_AHRS2(ahrs);
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
@ -852,14 +852,14 @@ const AP_Param::Info Copter::var_info[] = {
|
||||
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
|
||||
GOBJECT(rcmap, "RCMAP_", RCMapper),
|
||||
|
||||
// @Group: EKF_
|
||||
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
|
||||
GOBJECTN(EKF, NavEKF, "EKF_", NavEKF),
|
||||
|
||||
// @Group: EK2_
|
||||
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
|
||||
GOBJECTN(EKF2, NavEKF2, "EK2_", NavEKF2),
|
||||
|
||||
// @Group: EK3_
|
||||
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
|
||||
GOBJECTN(EKF3, NavEKF3, "EK3_", NavEKF3),
|
||||
|
||||
// @Group: MIS_
|
||||
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
||||
GOBJECT(mission, "MIS_", AP_Mission),
|
||||
|
@ -51,9 +51,10 @@ public:
|
||||
k_param_software_type,
|
||||
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
|
||||
k_param_ins, // libraries/AP_InertialSensor variables
|
||||
k_param_NavEKF2_old, // deprecated
|
||||
k_param_NavEKF2_old, // deprecated - remove
|
||||
k_param_NavEKF2,
|
||||
k_param_g2, // 2nd block of parameters
|
||||
k_param_NavEKF3,
|
||||
|
||||
// simulation
|
||||
k_param_sitl = 10,
|
||||
@ -110,7 +111,7 @@ public:
|
||||
k_param_angle_rate_max, // remove
|
||||
k_param_rssi_range, // unused, replaced by rssi_ library parameters
|
||||
k_param_rc_feel_rp,
|
||||
k_param_NavEKF, // Extended Kalman Filter Inertial Navigation Group
|
||||
k_param_NavEKF, // deprecated - remove
|
||||
k_param_mission, // mission library
|
||||
k_param_rc_13,
|
||||
k_param_rc_14,
|
||||
|
@ -14,7 +14,6 @@ LIBRARIES += AP_Math
|
||||
LIBRARIES += AP_InertialSensor
|
||||
LIBRARIES += AP_AccelCal
|
||||
LIBRARIES += AP_AHRS
|
||||
LIBRARIES += AP_NavEKF
|
||||
LIBRARIES += AP_NavEKF2
|
||||
LIBRARIES += AP_Mission
|
||||
LIBRARIES += AP_Rally
|
||||
|
Loading…
Reference in New Issue
Block a user