2015-11-26 23:53:29 +01:00
/****************************************************************************
*
2018-07-12 18:25:00 +01:00
* Copyright ( c ) 2015 - 2018 PX4 Development Team . All rights reserved .
2015-11-26 23:53:29 +01:00
*
* Redistribution and use in source and binary forms , with or without
* modification , are permitted provided that the following conditions
* are met :
*
* 1. Redistributions of source code must retain the above copyright
* notice , this list of conditions and the following disclaimer .
* 2. Redistributions in binary form must reproduce the above copyright
* notice , this list of conditions and the following disclaimer in
* the documentation and / or other materials provided with the
* distribution .
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission .
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* " AS IS " AND ANY EXPRESS OR IMPLIED WARRANTIES , INCLUDING , BUT NOT
* LIMITED TO , THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED . IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT , INDIRECT ,
* INCIDENTAL , SPECIAL , EXEMPLARY , OR CONSEQUENTIAL DAMAGES ( INCLUDING ,
* BUT NOT LIMITED TO , PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES ; LOSS
* OF USE , DATA , OR PROFITS ; OR BUSINESS INTERRUPTION ) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY , WHETHER IN CONTRACT , STRICT
* LIABILITY , OR TORT ( INCLUDING NEGLIGENCE OR OTHERWISE ) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE , EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE .
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/**
* @ file ekf2_main . cpp
* Implementation of the attitude and position estimator .
*
* @ author Roman Bapst
*/
2019-01-06 11:38:29 -05:00
# include <float.h>
2017-09-21 16:24:53 -04:00
# include <drivers/drv_hrt.h>
2018-06-28 17:28:03 -04:00
# include <lib/ecl/EKF/ekf.h>
# include <lib/mathlib/mathlib.h>
# include <lib/perf/perf_counter.h>
2015-11-26 23:53:29 +01:00
# include <px4_defines.h>
2017-05-10 10:32:45 +02:00
# include <px4_module.h>
2018-03-03 14:45:58 +01:00
# include <px4_module_params.h>
2015-11-26 23:53:29 +01:00
# include <px4_posix.h>
2017-09-05 12:56:53 -04:00
# include <px4_tasks.h>
2015-11-26 23:53:29 +01:00
# include <px4_time.h>
2018-03-03 14:45:58 +01:00
# include <uORB/Publication.hpp>
2019-08-29 15:48:46 +02:00
# include <uORB/PublicationMulti.hpp>
2019-05-30 11:46:37 -04:00
# include <uORB/Subscription.hpp>
2015-11-26 23:53:29 +01:00
# include <uORB/topics/airspeed.h>
2017-09-21 16:24:53 -04:00
# include <uORB/topics/distance_sensor.h>
2016-01-14 15:27:04 +01:00
# include <uORB/topics/ekf2_innovations.h>
2017-03-03 08:26:24 +01:00
# include <uORB/topics/ekf2_timestamps.h>
2018-07-23 02:18:30 +10:00
# include <uORB/topics/ekf_gps_position.h>
2017-09-21 16:24:53 -04:00
# include <uORB/topics/estimator_status.h>
2018-07-23 13:26:57 +10:00
# include <uORB/topics/ekf_gps_drift.h>
2018-07-23 02:18:30 +10:00
# include <uORB/topics/landing_target_pose.h>
2016-02-17 11:45:45 -08:00
# include <uORB/topics/optical_flow.h>
2017-09-21 16:24:53 -04:00
# include <uORB/topics/parameter_update.h>
# include <uORB/topics/sensor_bias.h>
# include <uORB/topics/sensor_combined.h>
# include <uORB/topics/sensor_selection.h>
2018-07-23 02:18:30 +10:00
# include <uORB/topics/vehicle_air_data.h>
2017-09-21 16:24:53 -04:00
# include <uORB/topics/vehicle_attitude.h>
# include <uORB/topics/vehicle_global_position.h>
# include <uORB/topics/vehicle_gps_position.h>
2016-02-25 17:00:39 +00:00
# include <uORB/topics/vehicle_land_detected.h>
2017-09-21 16:24:53 -04:00
# include <uORB/topics/vehicle_local_position.h>
2018-07-23 02:18:30 +10:00
# include <uORB/topics/vehicle_magnetometer.h>
2018-07-12 18:25:00 +01:00
# include <uORB/topics/vehicle_odometry.h>
2016-06-06 16:53:02 +02:00
# include <uORB/topics/vehicle_status.h>
2017-09-21 16:24:53 -04:00
# include <uORB/topics/wind_estimate.h>
2018-07-23 02:18:30 +10:00
// defines used to specify the mask position for use of different accuracy metrics in the GPS blending algorithm
# define BLEND_MASK_USE_SPD_ACC 1
# define BLEND_MASK_USE_HPOS_ACC 2
# define BLEND_MASK_USE_VPOS_ACC 4
// define max number of GPS receivers supported and 0 base instance used to access virtual 'blended' GPS solution
# define GPS_MAX_RECEIVERS 2
# define GPS_BLENDED_INSTANCE 2
2015-11-26 23:53:29 +01:00
2017-09-21 16:24:53 -04:00
using math : : constrain ;
2018-07-08 18:11:24 -04:00
using namespace time_literals ;
2015-11-26 23:53:29 +01:00
extern " C " __EXPORT int ekf2_main ( int argc , char * argv [ ] ) ;
2018-03-03 14:45:58 +01:00
class Ekf2 final : public ModuleBase < Ekf2 > , public ModuleParams
2015-11-26 23:53:29 +01:00
{
public :
Ekf2 ( ) ;
2018-04-11 22:33:34 -04:00
~ Ekf2 ( ) override ;
2015-11-26 23:53:29 +01:00
2017-05-10 10:32:45 +02:00
/** @see ModuleBase */
static int task_spawn ( int argc , char * argv [ ] ) ;
2015-11-26 23:53:29 +01:00
2017-05-10 10:32:45 +02:00
/** @see ModuleBase */
static Ekf2 * instantiate ( int argc , char * argv [ ] ) ;
2016-02-17 14:56:31 +01:00
2017-05-10 10:32:45 +02:00
/** @see ModuleBase */
static int custom_command ( int argc , char * argv [ ] ) ;
/** @see ModuleBase */
static int print_usage ( const char * reason = nullptr ) ;
/** @see ModuleBase::run() */
void run ( ) override ;
2015-11-26 23:53:29 +01:00
2017-09-21 16:24:53 -04:00
void set_replay_mode ( bool replay ) { _replay_mode = replay ; }
2015-11-26 23:53:29 +01:00
2017-05-10 10:32:45 +02:00
static void task_main_trampoline ( int argc , char * argv [ ] ) ;
2015-12-31 18:37:16 +11:00
2017-05-10 10:32:45 +02:00
int print_status ( ) override ;
2016-01-22 12:07:17 +01:00
2015-11-26 23:53:29 +01:00
private :
2019-05-30 11:46:37 -04:00
int getRangeSubIndex ( ) ; ///< get subscription index of first downward-facing range sensor
2017-10-04 11:55:09 +02:00
2018-03-03 14:45:58 +01:00
template < typename Param >
void update_mag_bias ( Param & mag_bias_param , int axis_index ) ;
2018-07-25 08:53:28 +10:00
template < typename Param >
bool update_mag_decl ( Param & mag_decl_param ) ;
2018-08-04 16:19:24 +02:00
bool publish_attitude ( const sensor_combined_s & sensors , const hrt_abstime & now ) ;
2018-03-14 13:46:19 -04:00
bool publish_wind_estimate ( const hrt_abstime & timestamp ) ;
const Vector3f get_vel_body_wind ( ) ;
2018-03-03 14:45:58 +01:00
2018-07-23 02:18:30 +10:00
/*
2018-09-29 23:23:19 +10:00
* Update the internal state estimate for a blended GPS solution that is a weighted average of the phsyical
* receiver solutions . This internal state cannot be used directly by estimators because if physical receivers
* have significant position differences , variation in receiver estimated accuracy will cause undesirable
2018-10-18 16:32:11 +02:00
* variation in the position solution .
2018-07-23 02:18:30 +10:00
*/
2018-09-29 23:23:19 +10:00
bool blend_gps_data ( ) ;
2018-07-23 02:18:30 +10:00
/*
* Calculate internal states used to blend GPS data from multiple receivers using weightings calculated
* by calc_blend_weights ( )
* States are written to _gps_state and _gps_blended_state class variables
*/
void update_gps_blend_states ( ) ;
/*
* The location in _gps_blended_state will move around as the relative accuracy changes .
* To mitigate this effect a low - pass filtered offset from each GPS location to the blended location is
* calculated .
*/
void update_gps_offsets ( ) ;
/*
* Apply the steady state physical receiver offsets calculated by update_gps_offsets ( ) .
*/
void apply_gps_offsets ( ) ;
/*
Calculate GPS output that is a blend of the offset corrected physical receiver data
*/
void calc_gps_blend_output ( ) ;
2018-09-07 10:42:29 +02:00
/*
* Calculate filtered WGS84 height from estimated AMSL height
*/
float filter_altitude_ellipsoid ( float amsl_hgt ) ;
2017-09-05 12:56:53 -04:00
bool _replay_mode = false ; ///< true when we use replay data from a log
2016-05-27 11:39:45 +10:00
2017-05-16 18:13:17 +10:00
// time slip monitoring
2017-09-05 12:56:53 -04:00
uint64_t _integrated_time_us = 0 ; ///< integral of gyro delta time from start (uSec)
uint64_t _start_time_us = 0 ; ///< system time at EKF start (uSec)
2017-11-07 15:55:50 -05:00
int64_t _last_time_slip_us = 0 ; ///< Last time slip (uSec)
2017-05-16 18:13:17 +10:00
2018-06-28 17:28:03 -04:00
perf_counter_t _perf_update_data ;
perf_counter_t _perf_ekf_update ;
2016-11-06 17:10:44 +11:00
// Initialise time stamps used to send sensor data to the EKF and for logging
2017-07-20 22:05:29 +10:00
uint8_t _invalid_mag_id_count = 0 ; ///< number of times an invalid magnetomer device ID has been detected
2016-11-06 17:10:44 +11:00
// Used to down sample magnetometer data
2017-09-21 16:24:53 -04:00
float _mag_data_sum [ 3 ] = { } ; ///< summed magnetometer readings (Gauss)
2017-07-20 22:05:29 +10:00
uint64_t _mag_time_sum_ms = 0 ; ///< summed magnetoemter time stamps (mSec)
uint8_t _mag_sample_count = 0 ; ///< number of magnetometer measurements summed during downsampling
2018-06-30 10:58:44 -04:00
int32_t _mag_time_ms_last_used = 0 ; ///< time stamp of the last averaged magnetometer measurement sent to the EKF (mSec)
2016-11-06 17:10:44 +11:00
2016-11-07 08:08:17 +11:00
// Used to down sample barometer data
2017-09-21 16:24:53 -04:00
float _balt_data_sum = 0.0f ; ///< summed pressure altitude readings (m)
2017-07-20 22:05:29 +10:00
uint64_t _balt_time_sum_ms = 0 ; ///< summed pressure altitude time stamps (mSec)
uint8_t _balt_sample_count = 0 ; ///< number of barometric altitude measurements summed
2016-11-07 09:20:30 +11:00
uint32_t _balt_time_ms_last_used =
2017-07-20 22:05:29 +10:00
0 ; ///< time stamp of the last averaged barometric altitude measurement sent to the EKF (mSec)
2016-11-07 08:08:17 +11:00
2017-03-30 09:21:47 +11:00
// Used to check, save and use learned magnetometer biases
2017-07-20 22:05:29 +10:00
hrt_abstime _last_magcal_us = 0 ; ///< last time the EKF was operating a mode that estimates magnetomer biases (uSec)
hrt_abstime _total_cal_time_us = 0 ; ///< accumulated calibration time since the last save
2017-09-05 12:56:53 -04:00
2017-07-20 22:05:29 +10:00
float _last_valid_mag_cal [ 3 ] = { } ; ///< last valid XYZ magnetometer bias estimates (mGauss)
bool _valid_cal_available [ 3 ] = { } ; ///< true when an unsaved valid calibration for the XYZ magnetometer bias is available
float _last_valid_variance [ 3 ] = { } ; ///< variances for the last valid magnetometer XYZ bias estimates (mGauss**2)
2017-03-30 09:21:47 +11:00
2018-07-25 08:53:28 +10:00
// Used to control saving of mag declination to be used on next startup
bool _mag_decl_saved = false ; ///< true when the magnetic declination has been saved
2017-05-16 20:55:50 +10:00
// Used to filter velocity innovations during pre-flight checks
2017-11-24 12:19:11 +11:00
bool _preflt_horiz_fail = false ; ///< true if preflight horizontal innovation checks are failed
bool _preflt_vert_fail = false ; ///< true if preflight vertical innovation checks are failed
bool _preflt_fail = false ; ///< true if any preflight innovation checks are failed
Vector2f _vel_ne_innov_lpf = { } ; ///< Preflight low pass filtered NE axis velocity innovations (m/sec)
float _vel_d_innov_lpf = { } ; ///< Preflight low pass filtered D axis velocity innovations (m/sec)
2017-07-20 22:05:29 +10:00
float _hgt_innov_lpf = 0.0f ; ///< Preflight low pass filtered height innovation (m)
2017-11-24 12:19:11 +11:00
float _yaw_innov_magnitude_lpf = 0.0f ; ///< Preflight low pass filtered yaw innovation magntitude (rad)
2017-09-05 12:56:53 -04:00
static constexpr float _innov_lpf_tau_inv = 0.2f ; ///< Preflight low pass filter time constant inverse (1/sec)
static constexpr float _vel_innov_test_lim =
0.5f ; ///< Maximum permissible velocity innovation to pass pre-flight checks (m/sec)
static constexpr float _hgt_innov_test_lim =
1.5f ; ///< Maximum permissible height innovation to pass pre-flight checks (m)
2017-12-07 11:49:24 +11:00
static constexpr float _nav_yaw_innov_test_lim =
0.25f ; ///< Maximum permissible yaw innovation to pass pre-flight checks when aiding inertial nav using NE frame observations (rad)
2017-11-24 12:19:11 +11:00
static constexpr float _yaw_innov_test_lim =
2017-12-07 22:08:30 +11:00
0.52f ; ///< Maximum permissible yaw innovation to pass pre-flight checks when not aiding inertial nav using NE frame observations (rad)
2017-07-20 22:05:29 +10:00
const float _vel_innov_spike_lim = 2.0f * _vel_innov_test_lim ; ///< preflight velocity innovation spike limit (m/sec)
const float _hgt_innov_spike_lim = 2.0f * _hgt_innov_test_lim ; ///< preflight position innovation spike limit (m)
2017-05-16 20:55:50 +10:00
2018-07-12 18:25:00 +01:00
// set pose/velocity as invalid if standard deviation is bigger than max_std_dev
// TODO: the user should be allowed to set these values by a parameter
static constexpr float ep_max_std_dev = 100.0f ; ///< Maximum permissible standard deviation for estimated position
2018-07-26 15:53:46 +01:00
static constexpr float eo_max_std_dev = 100.0f ; ///< Maximum permissible standard deviation for estimated orientation
2018-07-12 18:25:00 +01:00
//static constexpr float ev_max_std_dev = 100.0f; ///< Maximum permissible standard deviation for estimated velocity
2018-07-23 02:18:30 +10:00
// GPS blending and switching
gps_message _gps_state [ GPS_MAX_RECEIVERS ] { } ; ///< internal state data for the physical GPS
gps_message _gps_blended_state { } ; ///< internal state data for the blended GPS
gps_message _gps_output [ GPS_MAX_RECEIVERS + 1 ] { } ; ///< output state data for the physical and blended GPS
Vector2f _NE_pos_offset_m [ GPS_MAX_RECEIVERS ] = { } ; ///< Filtered North,East position offset from GPS instance to blended solution in _output_state.location (m)
float _hgt_offset_mm [ GPS_MAX_RECEIVERS ] = { } ; ///< Filtered height offset from GPS instance relative to blended solution in _output_state.location (mm)
Vector3f _blended_antenna_offset = { } ; ///< blended antenna offset
float _blend_weights [ GPS_MAX_RECEIVERS ] = { } ; ///< blend weight for each GPS. The blend weights must sum to 1.0 across all instances.
uint64_t _time_prev_us [ GPS_MAX_RECEIVERS ] = { } ; ///< the previous value of time_us for that GPS instance - used to detect new data.
uint8_t _gps_best_index = 0 ; ///< index of the physical receiver with the lowest reported error
uint8_t _gps_select_index = 0 ; ///< 0 = GPS1, 1 = GPS2, 2 = blended
2018-09-29 23:23:19 +10:00
uint8_t _gps_time_ref_index =
0 ; ///< index of the receiver that is used as the timing reference for the blending update
uint8_t _gps_oldest_index = 0 ; ///< index of the physical receiver with the oldest data
uint8_t _gps_newest_index = 0 ; ///< index of the physical receiver with the newest data
uint8_t _gps_slowest_index = 0 ; ///< index of the physical receiver with the slowest update rate
float _gps_dt [ GPS_MAX_RECEIVERS ] = { } ; ///< average time step in seconds.
bool _gps_new_output_data = false ; ///< true if there is new output data for the EKF
2019-04-26 21:33:36 +02:00
bool _had_valid_terrain = false ; ///< true if at any time there was a valid terrain estimate
2018-07-23 02:18:30 +10:00
2018-09-07 10:42:29 +02:00
int32_t _gps_alttitude_ellipsoid [ GPS_MAX_RECEIVERS ] { } ; ///< altitude in 1E-3 meters (millimeters) above ellipsoid
uint64_t _gps_alttitude_ellipsoid_previous_timestamp [ GPS_MAX_RECEIVERS ] { } ; ///< storage for previous timestamp to compute dt
float _wgs84_hgt_offset = 0 ; ///< height offset between AMSL and WGS84
2019-09-23 20:24:52 +02:00
// republished aligned external visual odometry
bool new_ev_data_received = false ;
vehicle_odometry_s _ev_odom { } ;
2019-05-30 11:46:37 -04:00
uORB : : Subscription _airdata_sub { ORB_ID ( vehicle_air_data ) } ;
uORB : : Subscription _airspeed_sub { ORB_ID ( airspeed ) } ;
uORB : : Subscription _ev_odom_sub { ORB_ID ( vehicle_visual_odometry ) } ;
uORB : : Subscription _landing_target_pose_sub { ORB_ID ( landing_target_pose ) } ;
uORB : : Subscription _magnetometer_sub { ORB_ID ( vehicle_magnetometer ) } ;
uORB : : Subscription _optical_flow_sub { ORB_ID ( optical_flow ) } ;
uORB : : Subscription _params_sub { ORB_ID ( parameter_update ) } ;
uORB : : Subscription _sensor_selection_sub { ORB_ID ( sensor_selection ) } ;
uORB : : Subscription _status_sub { ORB_ID ( vehicle_status ) } ;
uORB : : Subscription _vehicle_land_detected_sub { ORB_ID ( vehicle_land_detected ) } ;
2019-03-08 18:12:58 +03:00
int _sensors_sub { - 1 } ;
2018-04-11 22:33:34 -04:00
// because we can have several distance sensor instances with different orientations
2019-05-30 11:46:37 -04:00
uORB : : Subscription _range_finder_subs [ ORB_MULTI_MAX_INSTANCES ] { { ORB_ID ( distance_sensor ) , 0 } , { ORB_ID ( distance_sensor ) , 1 } , { ORB_ID ( distance_sensor ) , 2 } , { ORB_ID ( distance_sensor ) , 3 } } ;
2018-04-11 22:33:34 -04:00
int _range_finder_sub_index = - 1 ; // index for downward-facing range finder subscription
2018-07-23 02:18:30 +10:00
// because we can have multiple GPS instances
2019-05-30 11:46:37 -04:00
uORB : : Subscription _gps_subs [ GPS_MAX_RECEIVERS ] { { ORB_ID ( vehicle_gps_position ) , 0 } , { ORB_ID ( vehicle_gps_position ) , 1 } } ;
2019-03-08 18:12:58 +03:00
int _gps_orb_instance { - 1 } ;
2018-07-23 02:18:30 +10:00
2019-06-12 08:48:19 -04:00
uORB : : Publication < ekf2_innovations_s > _estimator_innovations_pub { ORB_ID ( ekf2_innovations ) } ;
uORB : : Publication < ekf2_timestamps_s > _ekf2_timestamps_pub { ORB_ID ( ekf2_timestamps ) } ;
uORB : : Publication < ekf_gps_drift_s > _ekf_gps_drift_pub { ORB_ID ( ekf_gps_drift ) } ;
uORB : : Publication < ekf_gps_position_s > _blended_gps_pub { ORB_ID ( ekf_gps_position ) } ;
uORB : : Publication < estimator_status_s > _estimator_status_pub { ORB_ID ( estimator_status ) } ;
uORB : : Publication < sensor_bias_s > _sensor_bias_pub { ORB_ID ( sensor_bias ) } ;
uORB : : Publication < vehicle_attitude_s > _att_pub { ORB_ID ( vehicle_attitude ) } ;
uORB : : Publication < vehicle_odometry_s > _vehicle_odometry_pub { ORB_ID ( vehicle_odometry ) } ;
2019-08-29 15:48:46 +02:00
uORB : : PublicationMulti < wind_estimate_s > _wind_pub { ORB_ID ( wind_estimate ) } ;
2019-06-12 08:48:19 -04:00
uORB : : PublicationData < vehicle_global_position_s > _vehicle_global_position_pub { ORB_ID ( vehicle_global_position ) } ;
uORB : : PublicationData < vehicle_local_position_s > _vehicle_local_position_pub { ORB_ID ( vehicle_local_position ) } ;
2019-09-23 20:24:52 +02:00
uORB : : PublicationData < vehicle_odometry_s > _vehicle_visual_odometry_aligned_pub { ORB_ID ( vehicle_visual_odometry_aligned ) } ;
2017-09-05 12:56:53 -04:00
2016-04-29 09:28:59 +02:00
Ekf _ekf ;
2016-01-31 22:28:19 +01:00
2017-07-20 22:05:29 +10:00
parameters * _params ; ///< pointer to ekf parameter struct (located in _ekf class instance)
2016-01-31 22:28:19 +01:00
2018-03-03 14:45:58 +01:00
DEFINE_PARAMETERS (
( ParamExtInt < px4 : : params : : EKF2_MIN_OBS_DT > )
2019-03-26 10:44:53 +01:00
_param_ekf2_min_obs_dt , ///< Maximum time delay of any sensor used to increase buffer length to handle large timing jitter (mSec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_MAG_DELAY > )
2019-03-26 10:44:53 +01:00
_param_ekf2_mag_delay , ///< magnetometer measurement delay relative to the IMU (mSec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_BARO_DELAY > )
2019-03-26 10:44:53 +01:00
_param_ekf2_baro_delay , ///< barometer height measurement delay relative to the IMU (mSec)
( ParamExtFloat < px4 : : params : : EKF2_GPS_DELAY > )
_param_ekf2_gps_delay , ///< GPS measurement delay relative to the IMU (mSec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_OF_DELAY > )
2019-03-26 10:44:53 +01:00
_param_ekf2_of_delay , ///< optical flow measurement delay relative to the IMU (mSec) - this is to the middle of the optical flow integration interval
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_RNG_DELAY > )
2019-03-26 10:44:53 +01:00
_param_ekf2_rng_delay , ///< range finder measurement delay relative to the IMU (mSec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_ASP_DELAY > )
2019-03-26 10:44:53 +01:00
_param_ekf2_asp_delay , ///< airspeed measurement delay relative to the IMU (mSec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_EV_DELAY > )
2019-03-26 10:44:53 +01:00
_param_ekf2_ev_delay , ///< off-board vision measurement delay relative to the IMU (mSec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_AVEL_DELAY > )
2019-03-26 10:44:53 +01:00
_param_ekf2_avel_delay , ///< auxillary velocity measurement delay relative to the IMU (mSec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_GYR_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gyr_noise , ///< IMU angular rate noise used for covariance prediction (rad/sec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_ACC_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_acc_noise , ///< IMU acceleration noise use for covariance prediction (m/sec**2)
2018-03-03 14:45:58 +01:00
// process noise
( ParamExtFloat < px4 : : params : : EKF2_GYR_B_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gyr_b_noise , ///< process noise for IMU rate gyro bias prediction (rad/sec**2)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_ACC_B_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_acc_b_noise , ///< process noise for IMU accelerometer bias prediction (m/sec**3)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_MAG_E_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_mag_e_noise , ///< process noise for earth magnetic field prediction (Gauss/sec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_MAG_B_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_mag_b_noise , ///< process noise for body magnetic field prediction (Gauss/sec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_WIND_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_wind_noise , ///< process noise for wind velocity prediction (m/sec**2)
( ParamExtFloat < px4 : : params : : EKF2_TERR_NOISE > ) _param_ekf2_terr_noise , ///< process noise for terrain offset (m/sec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_TERR_GRAD > )
2019-03-26 10:44:53 +01:00
_param_ekf2_terr_grad , ///< gradient of terrain used to estimate process noise due to changing position (m/m)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_GPS_V_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gps_v_noise , ///< minimum allowed observation noise for gps velocity fusion (m/sec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_GPS_P_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gps_p_noise , ///< minimum allowed observation noise for gps position fusion (m)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_NOAID_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_noaid_noise , ///< observation noise for non-aiding position fusion (m)
( ParamExtFloat < px4 : : params : : EKF2_BARO_NOISE > )
_param_ekf2_baro_noise , ///< observation noise for barometric height fusion (m)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_BARO_GATE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_baro_gate , ///< barometric height innovation consistency gate size (STD)
2019-03-05 17:53:39 +03:00
( ParamExtFloat < px4 : : params : : EKF2_GND_EFF_DZ > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gnd_eff_dz , ///< barometric deadzone range for negative innovations (m)
2019-03-15 08:59:44 +03:00
( ParamExtFloat < px4 : : params : : EKF2_GND_MAX_HGT > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gnd_max_hgt , ///< maximum height above the ground level for expected negative baro innovations (m)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_GPS_P_GATE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gps_p_gate , ///< GPS horizontal position innovation consistency gate size (STD)
( ParamExtFloat < px4 : : params : : EKF2_GPS_V_GATE > )
_param_ekf2_gps_v_gate , ///< GPS velocity innovation consistency gate size (STD)
( ParamExtFloat < px4 : : params : : EKF2_TAS_GATE > )
_param_ekf2_tas_gate , ///< True Airspeed innovation consistency gate size (STD)
2018-03-03 14:45:58 +01:00
// control of magnetometer fusion
( ParamExtFloat < px4 : : params : : EKF2_HEAD_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_head_noise , ///< measurement noise used for simple heading fusion (rad)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_MAG_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_mag_noise , ///< measurement noise used for 3-axis magnetoemeter fusion (Gauss)
( ParamExtFloat < px4 : : params : : EKF2_EAS_NOISE > )
_param_ekf2_eas_noise , ///< measurement noise used for airspeed fusion (m/sec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_BETA_GATE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_beta_gate , ///< synthetic sideslip innovation consistency gate size (STD)
( ParamExtFloat < px4 : : params : : EKF2_BETA_NOISE > ) _param_ekf2_beta_noise , ///< synthetic sideslip noise (rad)
( ParamExtFloat < px4 : : params : : EKF2_MAG_DECL > ) _param_ekf2_mag_decl , ///< magnetic declination (degrees)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_HDG_GATE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_hdg_gate , ///< heading fusion innovation consistency gate size (STD)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_MAG_GATE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_mag_gate , ///< magnetometer fusion innovation consistency gate size (STD)
2018-03-03 14:45:58 +01:00
( ParamExtInt < px4 : : params : : EKF2_DECL_TYPE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_decl_type , ///< bitmask used to control the handling of declination data
2018-03-03 14:45:58 +01:00
( ParamExtInt < px4 : : params : : EKF2_MAG_TYPE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_mag_type , ///< integer used to specify the type of magnetometer fusion used
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_MAG_ACCLIM > )
2019-03-26 10:44:53 +01:00
_param_ekf2_mag_acclim , ///< integer used to specify the type of magnetometer fusion used
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_MAG_YAWLIM > )
2019-03-26 10:44:53 +01:00
_param_ekf2_mag_yawlim , ///< yaw rate threshold used by mode select logic (rad/sec)
2018-03-03 14:45:58 +01:00
( ParamExtInt < px4 : : params : : EKF2_GPS_CHECK > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gps_check , ///< bitmask used to control which GPS quality checks are used
( ParamExtFloat < px4 : : params : : EKF2_REQ_EPH > ) _param_ekf2_req_eph , ///< maximum acceptable horiz position error (m)
( ParamExtFloat < px4 : : params : : EKF2_REQ_EPV > ) _param_ekf2_req_epv , ///< maximum acceptable vert position error (m)
( ParamExtFloat < px4 : : params : : EKF2_REQ_SACC > ) _param_ekf2_req_sacc , ///< maximum acceptable speed error (m/s)
( ParamExtInt < px4 : : params : : EKF2_REQ_NSATS > ) _param_ekf2_req_nsats , ///< minimum acceptable satellite count
( ParamExtFloat < px4 : : params : : EKF2_REQ_GDOP > )
_param_ekf2_req_gdop , ///< maximum acceptable geometric dilution of precision
( ParamExtFloat < px4 : : params : : EKF2_REQ_HDRIFT > )
_param_ekf2_req_hdrift , ///< maximum acceptable horizontal drift speed (m/s)
( ParamExtFloat < px4 : : params : : EKF2_REQ_VDRIFT > ) _param_ekf2_req_vdrift , ///< maximum acceptable vertical drift speed (m/s)
2018-03-03 14:45:58 +01:00
// measurement source control
( ParamExtInt < px4 : : params : : EKF2_AID_MASK > )
2019-03-26 10:44:53 +01:00
_param_ekf2_aid_mask , ///< bitmasked integer that selects which of the GPS and optical flow aiding sources will be used
( ParamExtInt < px4 : : params : : EKF2_HGT_MODE > ) _param_ekf2_hgt_mode , ///< selects the primary source for height data
2018-03-21 22:59:34 +11:00
( ParamExtInt < px4 : : params : : EKF2_NOAID_TOUT > )
2019-03-26 10:44:53 +01:00
_param_ekf2_noaid_tout , ///< maximum lapsed time from last fusion of measurements that constrain drift before the EKF will report the horizontal nav solution invalid (uSec)
2018-03-03 14:45:58 +01:00
// range finder fusion
2019-03-26 10:44:53 +01:00
( ParamExtFloat < px4 : : params : : EKF2_RNG_NOISE > )
_param_ekf2_rng_noise , ///< observation noise for range finder measurements (m)
( ParamExtFloat < px4 : : params : : EKF2_RNG_SFE > ) _param_ekf2_rng_sfe , ///< scale factor from range to range noise (m/m)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_RNG_GATE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_rng_gate , ///< range finder fusion innovation consistency gate size (STD)
( ParamExtFloat < px4 : : params : : EKF2_MIN_RNG > ) _param_ekf2_min_rng , ///< minimum valid value for range when on ground (m)
( ParamExtFloat < px4 : : params : : EKF2_RNG_PITCH > ) _param_ekf2_rng_pitch , ///< range sensor pitch offset (rad)
2018-03-03 14:45:58 +01:00
( ParamExtInt < px4 : : params : : EKF2_RNG_AID > )
2019-03-26 10:44:53 +01:00
_param_ekf2_rng_aid , ///< enables use of a range finder even if primary height source is not range finder
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_RNG_A_VMAX > )
2019-03-26 10:44:53 +01:00
_param_ekf2_rng_a_vmax , ///< maximum allowed horizontal velocity for range aid (m/s)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_RNG_A_HMAX > )
2019-03-26 10:44:53 +01:00
_param_ekf2_rng_a_hmax , ///< maximum allowed absolute altitude (AGL) for range aid (m)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_RNG_A_IGATE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_rng_a_igate , ///< gate size used for innovation consistency checks for range aid fusion (STD)
2018-03-03 14:45:58 +01:00
// vision estimate fusion
( ParamFloat < px4 : : params : : EKF2_EVP_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_evp_noise , ///< default position observation noise for exernal vision measurements (m)
2019-09-26 10:21:53 +02:00
( ParamFloat < px4 : : params : : EKF2_EVV_NOISE > )
_param_ekf2_evv_noise , ///< default velocity observation noise for exernal vision measurements (m/s)
2018-03-03 14:45:58 +01:00
( ParamFloat < px4 : : params : : EKF2_EVA_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_eva_noise , ///< default angular observation noise for exernal vision measurements (rad)
2019-09-26 10:21:53 +02:00
( ParamExtFloat < px4 : : params : : EKF2_EVV_GATE > )
_param_ekf2_evv_gate , ///< external vision velocity innovation consistency gate size (STD)
( ParamExtFloat < px4 : : params : : EKF2_EVP_GATE > )
_param_ekf2_evp_gate , ///< external vision position innovation consistency gate size (STD)
2018-03-03 14:45:58 +01:00
// optical flow fusion
( ParamExtFloat < px4 : : params : : EKF2_OF_N_MIN > )
2019-03-26 10:44:53 +01:00
_param_ekf2_of_n_min , ///< best quality observation noise for optical flow LOS rate measurements (rad/sec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_OF_N_MAX > )
2019-03-26 10:44:53 +01:00
_param_ekf2_of_n_max , ///< worst quality observation noise for optical flow LOS rate measurements (rad/sec)
( ParamExtInt < px4 : : params : : EKF2_OF_QMIN > )
_param_ekf2_of_qmin , ///< minimum acceptable quality integer from the flow sensor
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_OF_GATE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_of_gate , ///< optical flow fusion innovation consistency gate size (STD)
2018-03-03 14:45:58 +01:00
// sensor positions in body frame
2019-03-26 10:44:53 +01:00
( ParamExtFloat < px4 : : params : : EKF2_IMU_POS_X > ) _param_ekf2_imu_pos_x , ///< X position of IMU in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_IMU_POS_Y > ) _param_ekf2_imu_pos_y , ///< Y position of IMU in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_IMU_POS_Z > ) _param_ekf2_imu_pos_z , ///< Z position of IMU in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_GPS_POS_X > ) _param_ekf2_gps_pos_x , ///< X position of GPS antenna in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_GPS_POS_Y > ) _param_ekf2_gps_pos_y , ///< Y position of GPS antenna in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_GPS_POS_Z > ) _param_ekf2_gps_pos_z , ///< Z position of GPS antenna in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_RNG_POS_X > ) _param_ekf2_rng_pos_x , ///< X position of range finder in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_RNG_POS_Y > ) _param_ekf2_rng_pos_y , ///< Y position of range finder in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_RNG_POS_Z > ) _param_ekf2_rng_pos_z , ///< Z position of range finder in body frame (m)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_OF_POS_X > )
2019-03-26 10:44:53 +01:00
_param_ekf2_of_pos_x , ///< X position of optical flow sensor focal point in body frame (m)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_OF_POS_Y > )
2019-03-26 10:44:53 +01:00
_param_ekf2_of_pos_y , ///< Y position of optical flow sensor focal point in body frame (m)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_OF_POS_Z > )
2019-03-26 10:44:53 +01:00
_param_ekf2_of_pos_z , ///< Z position of optical flow sensor focal point in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_EV_POS_X > )
_param_ekf2_ev_pos_x , ///< X position of VI sensor focal point in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_EV_POS_Y > )
_param_ekf2_ev_pos_y , ///< Y position of VI sensor focal point in body frame (m)
( ParamExtFloat < px4 : : params : : EKF2_EV_POS_Z > )
_param_ekf2_ev_pos_z , ///< Z position of VI sensor focal point in body frame (m)
2018-03-03 14:45:58 +01:00
// control of airspeed and sideslip fusion
( ParamFloat < px4 : : params : : EKF2_ARSP_THR > )
2019-03-26 10:44:53 +01:00
_param_ekf2_arsp_thr , ///< A value of zero will disabled airspeed fusion. Any positive value sets the minimum airspeed which will be used (m/sec)
( ParamInt < px4 : : params : : EKF2_FUSE_BETA > )
_param_ekf2_fuse_beta , ///< Controls synthetic sideslip fusion, 0 disables, 1 enables
2018-03-03 14:45:58 +01:00
// output predictor filter time constants
( ParamExtFloat < px4 : : params : : EKF2_TAU_VEL > )
2019-03-26 10:44:53 +01:00
_param_ekf2_tau_vel , ///< time constant used by the output velocity complementary filter (sec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_TAU_POS > )
2019-03-26 10:44:53 +01:00
_param_ekf2_tau_pos , ///< time constant used by the output position complementary filter (sec)
2018-03-03 14:45:58 +01:00
2018-03-21 22:59:34 +11:00
// IMU switch on bias parameters
2019-03-26 10:44:53 +01:00
( ParamExtFloat < px4 : : params : : EKF2_GBIAS_INIT > )
_param_ekf2_gbias_init , ///< 1-sigma gyro bias uncertainty at switch on (rad/sec)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_ABIAS_INIT > )
2019-03-26 10:44:53 +01:00
_param_ekf2_abias_init , ///< 1-sigma accelerometer bias uncertainty at switch on (m/sec**2)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_ANGERR_INIT > )
2019-03-26 10:44:53 +01:00
_param_ekf2_angerr_init , ///< 1-sigma tilt error after initial alignment using gravity vector (rad)
2018-03-03 14:45:58 +01:00
// EKF saved XYZ magnetometer bias values
2019-03-26 10:44:53 +01:00
( ParamFloat < px4 : : params : : EKF2_MAGBIAS_X > ) _param_ekf2_magbias_x , ///< X magnetometer bias (mGauss)
( ParamFloat < px4 : : params : : EKF2_MAGBIAS_Y > ) _param_ekf2_magbias_y , ///< Y magnetometer bias (mGauss)
( ParamFloat < px4 : : params : : EKF2_MAGBIAS_Z > ) _param_ekf2_magbias_z , ///< Z magnetometer bias (mGauss)
( ParamInt < px4 : : params : : EKF2_MAGBIAS_ID > )
_param_ekf2_magbias_id , ///< ID of the magnetometer sensor used to learn the bias values
2018-03-03 14:45:58 +01:00
( ParamFloat < px4 : : params : : EKF2_MAGB_VREF > )
2019-03-26 10:44:53 +01:00
_param_ekf2_magb_vref , ///< Assumed error variance of previously saved magnetometer bias estimates (mGauss**2)
2018-03-03 14:45:58 +01:00
( ParamFloat < px4 : : params : : EKF2_MAGB_K > )
2019-03-26 10:44:53 +01:00
_param_ekf2_magb_k , ///< maximum fraction of the learned magnetometer bias that is saved at each disarm
2018-03-03 14:45:58 +01:00
// EKF accel bias learning control
2019-03-26 10:44:53 +01:00
( ParamExtFloat < px4 : : params : : EKF2_ABL_LIM > ) _param_ekf2_abl_lim , ///< Accelerometer bias learning limit (m/s**2)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_ABL_ACCLIM > )
2019-03-26 10:44:53 +01:00
_param_ekf2_abl_acclim , ///< Maximum IMU accel magnitude that allows IMU bias learning (m/s**2)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_ABL_GYRLIM > )
2019-03-26 10:44:53 +01:00
_param_ekf2_abl_gyrlim , ///< Maximum IMU gyro angular rate magnitude that allows IMU bias learning (m/s**2)
2018-03-03 14:45:58 +01:00
( ParamExtFloat < px4 : : params : : EKF2_ABL_TAU > )
2019-03-26 10:44:53 +01:00
_param_ekf2_abl_tau , ///< Time constant used to inhibit IMU delta velocity bias learning (sec)
2018-03-03 14:45:58 +01:00
// Multi-rotor drag specific force fusion
( ParamExtFloat < px4 : : params : : EKF2_DRAG_NOISE > )
2019-03-26 10:44:53 +01:00
_param_ekf2_drag_noise , ///< observation noise variance for drag specific force measurements (m/sec**2)**2
( ParamExtFloat < px4 : : params : : EKF2_BCOEF_X > ) _param_ekf2_bcoef_x , ///< ballistic coefficient along the X-axis (kg/m**2)
( ParamExtFloat < px4 : : params : : EKF2_BCOEF_Y > ) _param_ekf2_bcoef_y , ///< ballistic coefficient along the Y-axis (kg/m**2)
2018-03-03 14:45:58 +01:00
// Corrections for static pressure position error where Ps_error = Ps_meas - Ps_truth
// Coef = Ps_error / Pdynamic, where Pdynamic = 1/2 * density * TAS**2
2019-03-26 10:44:53 +01:00
( ParamFloat < px4 : : params : : EKF2_ASPD_MAX > )
_param_ekf2_aspd_max , ///< upper limit on airspeed used for correction (m/s**2)
2018-03-03 14:45:58 +01:00
( ParamFloat < px4 : : params : : EKF2_PCOEF_XP > )
2019-03-26 10:44:53 +01:00
_param_ekf2_pcoef_xp , ///< static pressure position error coefficient along the positive X body axis
2018-03-03 14:45:58 +01:00
( ParamFloat < px4 : : params : : EKF2_PCOEF_XN > )
2019-03-26 10:44:53 +01:00
_param_ekf2_pcoef_xn , ///< static pressure position error coefficient along the negative X body axis
2019-02-27 09:11:40 +11:00
( ParamFloat < px4 : : params : : EKF2_PCOEF_YP > )
2019-03-26 10:44:53 +01:00
_param_ekf2_pcoef_yp , ///< static pressure position error coefficient along the positive Y body axis
2019-02-27 09:11:40 +11:00
( ParamFloat < px4 : : params : : EKF2_PCOEF_YN > )
2019-03-26 10:44:53 +01:00
_param_ekf2_pcoef_yn , ///< static pressure position error coefficient along the negative Y body axis
2018-03-03 14:45:58 +01:00
( ParamFloat < px4 : : params : : EKF2_PCOEF_Z > )
2019-03-26 10:44:53 +01:00
_param_ekf2_pcoef_z , ///< static pressure position error coefficient along the Z body axis
2018-07-23 02:18:30 +10:00
// GPS blending
( ParamInt < px4 : : params : : EKF2_GPS_MASK > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gps_mask , ///< mask defining when GPS accuracy metrics are used to calculate the blend ratio
2018-07-23 02:18:30 +10:00
( ParamFloat < px4 : : params : : EKF2_GPS_TAU > )
2019-03-26 10:44:53 +01:00
_param_ekf2_gps_tau , ///< time constant controlling how rapidly the offset used to bring GPS solutions together is allowed to change (sec)
2018-07-23 13:26:57 +10:00
// Test used to determine if the vehicle is static or moving
( ParamExtFloat < px4 : : params : : EKF2_MOVE_TEST > )
2019-05-15 10:17:28 +02:00
_param_ekf2_move_test , ///< scaling applied to IMU data thresholds used to determine if the vehicle is static or moving.
( ParamFloat < px4 : : params : : EKF2_REQ_GPS_H > ) _param_ekf2_req_gps_h ///< Required GPS health time
2018-07-23 13:26:57 +10:00
2018-03-03 14:45:58 +01:00
)
2017-08-01 07:29:08 +10:00
2015-11-26 23:53:29 +01:00
} ;
2015-12-10 16:38:51 +01:00
Ekf2 : : Ekf2 ( ) :
2018-03-03 14:45:58 +01:00
ModuleParams ( nullptr ) ,
2018-06-28 17:28:03 -04:00
_perf_update_data ( perf_alloc_once ( PC_ELAPSED , " EKF2 data acquisition " ) ) ,
_perf_ekf_update ( perf_alloc_once ( PC_ELAPSED , " EKF2 update " ) ) ,
2016-04-29 09:28:59 +02:00
_params ( _ekf . getParamHandle ( ) ) ,
2019-03-26 10:44:53 +01:00
_param_ekf2_min_obs_dt ( _params - > sensor_interval_min_ms ) ,
_param_ekf2_mag_delay ( _params - > mag_delay_ms ) ,
_param_ekf2_baro_delay ( _params - > baro_delay_ms ) ,
_param_ekf2_gps_delay ( _params - > gps_delay_ms ) ,
_param_ekf2_of_delay ( _params - > flow_delay_ms ) ,
_param_ekf2_rng_delay ( _params - > range_delay_ms ) ,
_param_ekf2_asp_delay ( _params - > airspeed_delay_ms ) ,
_param_ekf2_ev_delay ( _params - > ev_delay_ms ) ,
_param_ekf2_avel_delay ( _params - > auxvel_delay_ms ) ,
_param_ekf2_gyr_noise ( _params - > gyro_noise ) ,
_param_ekf2_acc_noise ( _params - > accel_noise ) ,
_param_ekf2_gyr_b_noise ( _params - > gyro_bias_p_noise ) ,
_param_ekf2_acc_b_noise ( _params - > accel_bias_p_noise ) ,
_param_ekf2_mag_e_noise ( _params - > mage_p_noise ) ,
_param_ekf2_mag_b_noise ( _params - > magb_p_noise ) ,
_param_ekf2_wind_noise ( _params - > wind_vel_p_noise ) ,
_param_ekf2_terr_noise ( _params - > terrain_p_noise ) ,
_param_ekf2_terr_grad ( _params - > terrain_gradient ) ,
_param_ekf2_gps_v_noise ( _params - > gps_vel_noise ) ,
_param_ekf2_gps_p_noise ( _params - > gps_pos_noise ) ,
_param_ekf2_noaid_noise ( _params - > pos_noaid_noise ) ,
_param_ekf2_baro_noise ( _params - > baro_noise ) ,
_param_ekf2_baro_gate ( _params - > baro_innov_gate ) ,
_param_ekf2_gnd_eff_dz ( _params - > gnd_effect_deadzone ) ,
_param_ekf2_gnd_max_hgt ( _params - > gnd_effect_max_hgt ) ,
2019-09-26 10:21:53 +02:00
_param_ekf2_gps_p_gate ( _params - > gps_pos_innov_gate ) ,
_param_ekf2_gps_v_gate ( _params - > gps_vel_innov_gate ) ,
2019-03-26 10:44:53 +01:00
_param_ekf2_tas_gate ( _params - > tas_innov_gate ) ,
_param_ekf2_head_noise ( _params - > mag_heading_noise ) ,
_param_ekf2_mag_noise ( _params - > mag_noise ) ,
_param_ekf2_eas_noise ( _params - > eas_noise ) ,
_param_ekf2_beta_gate ( _params - > beta_innov_gate ) ,
_param_ekf2_beta_noise ( _params - > beta_noise ) ,
_param_ekf2_mag_decl ( _params - > mag_declination_deg ) ,
_param_ekf2_hdg_gate ( _params - > heading_innov_gate ) ,
_param_ekf2_mag_gate ( _params - > mag_innov_gate ) ,
_param_ekf2_decl_type ( _params - > mag_declination_source ) ,
_param_ekf2_mag_type ( _params - > mag_fusion_type ) ,
_param_ekf2_mag_acclim ( _params - > mag_acc_gate ) ,
_param_ekf2_mag_yawlim ( _params - > mag_yaw_rate_gate ) ,
_param_ekf2_gps_check ( _params - > gps_check_mask ) ,
_param_ekf2_req_eph ( _params - > req_hacc ) ,
_param_ekf2_req_epv ( _params - > req_vacc ) ,
_param_ekf2_req_sacc ( _params - > req_sacc ) ,
_param_ekf2_req_nsats ( _params - > req_nsats ) ,
_param_ekf2_req_gdop ( _params - > req_gdop ) ,
_param_ekf2_req_hdrift ( _params - > req_hdrift ) ,
_param_ekf2_req_vdrift ( _params - > req_vdrift ) ,
_param_ekf2_aid_mask ( _params - > fusion_mode ) ,
_param_ekf2_hgt_mode ( _params - > vdist_sensor_type ) ,
_param_ekf2_noaid_tout ( _params - > valid_timeout_max ) ,
_param_ekf2_rng_noise ( _params - > range_noise ) ,
_param_ekf2_rng_sfe ( _params - > range_noise_scaler ) ,
_param_ekf2_rng_gate ( _params - > range_innov_gate ) ,
_param_ekf2_min_rng ( _params - > rng_gnd_clearance ) ,
_param_ekf2_rng_pitch ( _params - > rng_sens_pitch ) ,
_param_ekf2_rng_aid ( _params - > range_aid ) ,
_param_ekf2_rng_a_vmax ( _params - > max_vel_for_range_aid ) ,
_param_ekf2_rng_a_hmax ( _params - > max_hagl_for_range_aid ) ,
_param_ekf2_rng_a_igate ( _params - > range_aid_innov_gate ) ,
2019-09-26 10:21:53 +02:00
_param_ekf2_evv_gate ( _params - > ev_vel_innov_gate ) ,
_param_ekf2_evp_gate ( _params - > ev_pos_innov_gate ) ,
2019-03-26 10:44:53 +01:00
_param_ekf2_of_n_min ( _params - > flow_noise ) ,
_param_ekf2_of_n_max ( _params - > flow_noise_qual_min ) ,
_param_ekf2_of_qmin ( _params - > flow_qual_min ) ,
_param_ekf2_of_gate ( _params - > flow_innov_gate ) ,
_param_ekf2_imu_pos_x ( _params - > imu_pos_body ( 0 ) ) ,
_param_ekf2_imu_pos_y ( _params - > imu_pos_body ( 1 ) ) ,
_param_ekf2_imu_pos_z ( _params - > imu_pos_body ( 2 ) ) ,
_param_ekf2_gps_pos_x ( _params - > gps_pos_body ( 0 ) ) ,
_param_ekf2_gps_pos_y ( _params - > gps_pos_body ( 1 ) ) ,
_param_ekf2_gps_pos_z ( _params - > gps_pos_body ( 2 ) ) ,
_param_ekf2_rng_pos_x ( _params - > rng_pos_body ( 0 ) ) ,
_param_ekf2_rng_pos_y ( _params - > rng_pos_body ( 1 ) ) ,
_param_ekf2_rng_pos_z ( _params - > rng_pos_body ( 2 ) ) ,
_param_ekf2_of_pos_x ( _params - > flow_pos_body ( 0 ) ) ,
_param_ekf2_of_pos_y ( _params - > flow_pos_body ( 1 ) ) ,
_param_ekf2_of_pos_z ( _params - > flow_pos_body ( 2 ) ) ,
_param_ekf2_ev_pos_x ( _params - > ev_pos_body ( 0 ) ) ,
_param_ekf2_ev_pos_y ( _params - > ev_pos_body ( 1 ) ) ,
_param_ekf2_ev_pos_z ( _params - > ev_pos_body ( 2 ) ) ,
_param_ekf2_tau_vel ( _params - > vel_Tau ) ,
_param_ekf2_tau_pos ( _params - > pos_Tau ) ,
_param_ekf2_gbias_init ( _params - > switch_on_gyro_bias ) ,
_param_ekf2_abias_init ( _params - > switch_on_accel_bias ) ,
_param_ekf2_angerr_init ( _params - > initial_tilt_err ) ,
_param_ekf2_abl_lim ( _params - > acc_bias_lim ) ,
_param_ekf2_abl_acclim ( _params - > acc_bias_learn_acc_lim ) ,
_param_ekf2_abl_gyrlim ( _params - > acc_bias_learn_gyr_lim ) ,
_param_ekf2_abl_tau ( _params - > acc_bias_learn_tc ) ,
_param_ekf2_drag_noise ( _params - > drag_noise ) ,
_param_ekf2_bcoef_x ( _params - > bcoef_x ) ,
_param_ekf2_bcoef_y ( _params - > bcoef_y ) ,
_param_ekf2_move_test ( _params - > is_moving_scaler )
2015-11-26 23:53:29 +01:00
{
2018-04-11 22:33:34 -04:00
_sensors_sub = orb_subscribe ( ORB_ID ( sensor_combined ) ) ;
// initialise parameter cache
updateParams ( ) ;
2019-05-15 10:17:28 +02:00
_ekf . set_min_required_gps_health_time ( _param_ekf2_req_gps_h . get ( ) * 1 _s ) ;
2018-04-11 22:33:34 -04:00
}
Ekf2 : : ~ Ekf2 ( )
{
2018-06-28 17:28:03 -04:00
perf_free ( _perf_update_data ) ;
perf_free ( _perf_ekf_update ) ;
2018-04-11 22:33:34 -04:00
orb_unsubscribe ( _sensors_sub ) ;
2015-11-26 23:53:29 +01:00
}
2017-05-10 10:32:45 +02:00
int Ekf2 : : print_status ( )
2015-12-31 18:37:16 +11:00
{
2018-06-28 17:28:03 -04:00
PX4_INFO ( " local position: %s " , ( _ekf . local_position_is_valid ( ) ) ? " valid " : " invalid " ) ;
PX4_INFO ( " global position: %s " , ( _ekf . global_position_is_valid ( ) ) ? " valid " : " invalid " ) ;
2017-11-07 15:55:50 -05:00
PX4_INFO ( " time slip: % " PRId64 " us " , _last_time_slip_us ) ;
2018-06-28 17:28:03 -04:00
perf_print_counter ( _perf_update_data ) ;
perf_print_counter ( _perf_ekf_update ) ;
2017-05-10 10:32:45 +02:00
return 0 ;
2015-12-31 18:37:16 +11:00
}
2018-03-03 14:45:58 +01:00
template < typename Param >
void Ekf2 : : update_mag_bias ( Param & mag_bias_param , int axis_index )
{
if ( _valid_cal_available [ axis_index ] ) {
// calculate weighting using ratio of variances and update stored bias values
2019-03-26 10:44:53 +01:00
const float weighting = constrain ( _param_ekf2_magb_vref . get ( ) / ( _param_ekf2_magb_vref . get ( ) +
_last_valid_variance [ axis_index ] ) , 0.0f , _param_ekf2_magb_k . get ( ) ) ;
2018-03-03 14:45:58 +01:00
const float mag_bias_saved = mag_bias_param . get ( ) ;
_last_valid_mag_cal [ axis_index ] = weighting * _last_valid_mag_cal [ axis_index ] + mag_bias_saved ;
mag_bias_param . set ( _last_valid_mag_cal [ axis_index ] ) ;
mag_bias_param . commit_no_notification ( ) ;
_valid_cal_available [ axis_index ] = false ;
}
}
2018-07-25 08:53:28 +10:00
template < typename Param >
bool Ekf2 : : update_mag_decl ( Param & mag_decl_param )
{
// update stored declination value
float declination_deg ;
if ( _ekf . get_mag_decl_deg ( & declination_deg ) ) {
mag_decl_param . set ( declination_deg ) ;
mag_decl_param . commit_no_notification ( ) ;
return true ;
}
return false ;
}
2017-05-10 10:32:45 +02:00
void Ekf2 : : run ( )
2015-11-26 23:53:29 +01:00
{
2017-10-27 15:45:53 +11:00
bool imu_bias_reset_request = false ;
2017-07-09 12:14:18 -04:00
px4_pollfd_struct_t fds [ 1 ] = { } ;
2018-04-11 22:33:34 -04:00
fds [ 0 ] . fd = _sensors_sub ;
2015-11-26 23:53:29 +01:00
fds [ 0 ] . events = POLLIN ;
2016-02-17 14:56:31 +01:00
// initialize data structures outside of loop
// because they will else not always be
// properly populated
sensor_combined_s sensors = { } ;
2016-05-10 10:18:17 +10:00
vehicle_land_detected_s vehicle_land_detected = { } ;
2016-11-01 09:12:17 +01:00
vehicle_status_s vehicle_status = { } ;
2017-03-30 09:21:47 +11:00
sensor_selection_s sensor_selection = { } ;
2016-05-26 23:29:19 +10:00
2017-05-10 10:32:45 +02:00
while ( ! should_exit ( ) ) {
2016-01-22 14:21:19 +01:00
int ret = px4_poll ( fds , sizeof ( fds ) / sizeof ( fds [ 0 ] ) , 1000 ) ;
2015-11-26 23:53:29 +01:00
2017-07-09 12:14:18 -04:00
if ( ! ( fds [ 0 ] . revents & POLLIN ) ) {
// no new data
continue ;
}
2015-11-26 23:53:29 +01:00
if ( ret < 0 ) {
// Poll error, sleep and try again
2018-10-04 06:51:04 +02:00
px4_usleep ( 10000 ) ;
2015-11-26 23:53:29 +01:00
continue ;
2016-01-22 14:21:19 +01:00
} else if ( ret = = 0 ) {
2015-11-26 23:53:29 +01:00
// Poll timeout or no new data, do nothing
continue ;
}
2018-06-28 17:28:03 -04:00
perf_begin ( _perf_update_data ) ;
2019-05-30 11:46:37 -04:00
if ( _params_sub . updated ( ) ) {
2016-01-22 11:43:38 +01:00
// read from param to clear updated flag
2017-07-09 12:14:18 -04:00
parameter_update_s update ;
2019-05-30 11:46:37 -04:00
_params_sub . copy ( & update ) ;
2016-01-22 11:43:38 +01:00
updateParams ( ) ;
}
2016-01-09 09:11:31 +01:00
2018-04-11 22:33:34 -04:00
orb_copy ( ORB_ID ( sensor_combined ) , _sensors_sub , & sensors ) ;
2016-06-06 16:53:02 +02:00
2018-03-19 14:17:16 -04:00
// ekf2_timestamps (using 0.1 ms relative timestamps)
ekf2_timestamps_s ekf2_timestamps = { } ;
ekf2_timestamps . timestamp = sensors . timestamp ;
2016-06-06 16:53:02 +02:00
2018-03-19 14:17:16 -04:00
ekf2_timestamps . airspeed_timestamp_rel = ekf2_timestamps_s : : RELATIVE_TIMESTAMP_INVALID ;
ekf2_timestamps . distance_sensor_timestamp_rel = ekf2_timestamps_s : : RELATIVE_TIMESTAMP_INVALID ;
ekf2_timestamps . gps_timestamp_rel = ekf2_timestamps_s : : RELATIVE_TIMESTAMP_INVALID ;
ekf2_timestamps . optical_flow_timestamp_rel = ekf2_timestamps_s : : RELATIVE_TIMESTAMP_INVALID ;
ekf2_timestamps . vehicle_air_data_timestamp_rel = ekf2_timestamps_s : : RELATIVE_TIMESTAMP_INVALID ;
ekf2_timestamps . vehicle_magnetometer_timestamp_rel = ekf2_timestamps_s : : RELATIVE_TIMESTAMP_INVALID ;
2018-07-12 18:25:00 +01:00
ekf2_timestamps . visual_odometry_timestamp_rel = ekf2_timestamps_s : : RELATIVE_TIMESTAMP_INVALID ;
2016-06-06 16:53:02 +02:00
2018-03-19 14:17:16 -04:00
// update all other topics if they have new data
2019-05-30 11:46:37 -04:00
if ( _status_sub . update ( & vehicle_status ) ) {
2019-06-11 12:54:22 +02:00
bool is_fixed_wing = vehicle_status . vehicle_type = = vehicle_status_s : : VEHICLE_TYPE_FIXED_WING ;
2019-05-30 11:46:37 -04:00
// only fuse synthetic sideslip measurements if conditions are met
2019-06-11 12:54:22 +02:00
_ekf . set_fuse_beta_flag ( is_fixed_wing & & ( _param_ekf2_fuse_beta . get ( ) = = 1 ) ) ;
2015-11-26 23:53:29 +01:00
2019-05-30 11:46:37 -04:00
// let the EKF know if the vehicle motion is that of a fixed wing (forward flight only relative to wind)
2019-06-11 12:54:22 +02:00
_ekf . set_is_fixed_wing ( is_fixed_wing ) ;
2015-11-26 23:53:29 +01:00
}
2017-10-30 15:47:12 +11:00
// Always update sensor selction first time through if time stamp is non zero
2019-05-30 11:46:37 -04:00
if ( _sensor_selection_sub . updated ( ) | | ( sensor_selection . timestamp = = 0 ) ) {
const sensor_selection_s sensor_selection_prev = sensor_selection ;
2017-10-26 15:14:32 -04:00
2019-05-30 11:46:37 -04:00
if ( _sensor_selection_sub . copy ( & sensor_selection ) ) {
2018-03-19 14:17:16 -04:00
if ( ( sensor_selection_prev . timestamp > 0 ) & & ( sensor_selection . timestamp > sensor_selection_prev . timestamp ) ) {
if ( sensor_selection . accel_device_id ! = sensor_selection_prev . accel_device_id ) {
PX4_WARN ( " accel id changed, resetting IMU bias " ) ;
imu_bias_reset_request = true ;
}
2017-10-26 15:14:32 -04:00
2018-03-19 14:17:16 -04:00
if ( sensor_selection . gyro_device_id ! = sensor_selection_prev . gyro_device_id ) {
PX4_WARN ( " gyro id changed, resetting IMU bias " ) ;
imu_bias_reset_request = true ;
}
2017-10-26 15:14:32 -04:00
}
}
2017-09-05 12:56:53 -04:00
}
2017-10-27 15:45:53 +11:00
// attempt reset until successful
if ( imu_bias_reset_request ) {
imu_bias_reset_request = ! _ekf . reset_imu_bias ( ) ;
}
2019-02-06 09:16:44 -05:00
const hrt_abstime now = sensors . timestamp ;
2016-02-17 14:56:31 +01:00
2015-11-26 23:53:29 +01:00
// push imu data into estimator
2019-02-06 09:17:31 -05:00
imuSample imu_sample_new ;
imu_sample_new . time_us = now ;
imu_sample_new . delta_ang_dt = sensors . gyro_integral_dt * 1.e-6 f ;
imu_sample_new . delta_ang = Vector3f { sensors . gyro_rad } * imu_sample_new . delta_ang_dt ;
imu_sample_new . delta_vel_dt = sensors . accelerometer_integral_dt * 1.e-6 f ;
imu_sample_new . delta_vel = Vector3f { sensors . accelerometer_m_s2 } * imu_sample_new . delta_vel_dt ;
_ekf . setIMUData ( imu_sample_new ) ;
2015-11-26 23:53:29 +01:00
2018-07-08 18:11:24 -04:00
// publish attitude immediately (uses quaternion from output predictor)
2018-08-04 16:19:24 +02:00
publish_attitude ( sensors , now ) ;
2018-07-08 18:11:24 -04:00
2015-11-26 23:53:29 +01:00
// read mag data
2019-05-30 11:46:37 -04:00
if ( _magnetometer_sub . updated ( ) ) {
2018-03-19 14:17:16 -04:00
vehicle_magnetometer_s magnetometer ;
2016-11-06 17:10:44 +11:00
2019-05-30 11:46:37 -04:00
if ( _magnetometer_sub . copy ( & magnetometer ) ) {
2017-03-30 09:21:47 +11:00
// Reset learned bias parameters if there has been a persistant change in magnetometer ID
// Do not reset parmameters when armed to prevent potential time slips casued by parameter set
// and notification events
// Check if there has been a persistant change in magnetometer ID
2019-03-26 10:44:53 +01:00
if ( sensor_selection . mag_device_id ! = 0 & & sensor_selection . mag_device_id ! = ( uint32_t ) _param_ekf2_magbias_id . get ( ) ) {
2017-03-30 09:21:47 +11:00
if ( _invalid_mag_id_count < 200 ) {
_invalid_mag_id_count + + ;
}
} else {
if ( _invalid_mag_id_count > 0 ) {
_invalid_mag_id_count - - ;
}
}
if ( ( vehicle_status . arming_state ! = vehicle_status_s : : ARMING_STATE_ARMED ) & & ( _invalid_mag_id_count > 100 ) ) {
// the sensor ID used for the last saved mag bias is not confirmed to be the same as the current sensor ID
// this means we need to reset the learned bias values to zero
2019-03-26 10:44:53 +01:00
_param_ekf2_magbias_x . set ( 0.f ) ;
_param_ekf2_magbias_x . commit_no_notification ( ) ;
_param_ekf2_magbias_y . set ( 0.f ) ;
_param_ekf2_magbias_y . commit_no_notification ( ) ;
_param_ekf2_magbias_z . set ( 0.f ) ;
_param_ekf2_magbias_z . commit_no_notification ( ) ;
_param_ekf2_magbias_id . set ( sensor_selection . mag_device_id ) ;
_param_ekf2_magbias_id . commit ( ) ;
2017-09-21 16:24:53 -04:00
2017-03-30 09:21:47 +11:00
_invalid_mag_id_count = 0 ;
2019-03-26 10:44:53 +01:00
PX4_INFO ( " Mag sensor ID changed to %i " , _param_ekf2_magbias_id . get ( ) ) ;
2017-03-30 09:21:47 +11:00
}
2016-11-07 10:56:43 +11:00
// If the time last used by the EKF is less than specified, then accumulate the
2017-04-22 08:15:59 +10:00
// data and push the average when the specified interval is reached.
2018-02-18 11:44:21 -05:00
_mag_time_sum_ms + = magnetometer . timestamp / 1000 ;
2016-11-06 17:10:44 +11:00
_mag_sample_count + + ;
2018-02-18 11:44:21 -05:00
_mag_data_sum [ 0 ] + = magnetometer . magnetometer_ga [ 0 ] ;
_mag_data_sum [ 1 ] + = magnetometer . magnetometer_ga [ 1 ] ;
_mag_data_sum [ 2 ] + = magnetometer . magnetometer_ga [ 2 ] ;
2018-06-30 10:58:44 -04:00
int32_t mag_time_ms = _mag_time_sum_ms / _mag_sample_count ;
2016-11-07 09:20:30 +11:00
2018-06-30 10:58:44 -04:00
if ( ( mag_time_ms - _mag_time_ms_last_used ) > _params - > sensor_interval_min_ms ) {
2017-11-07 15:55:50 -05:00
const float mag_sample_count_inv = 1.0f / _mag_sample_count ;
2017-03-30 09:21:47 +11:00
// calculate mean of measurements and correct for learned bias offsets
2019-03-26 10:44:53 +01:00
float mag_data_avg_ga [ 3 ] = { _mag_data_sum [ 0 ] * mag_sample_count_inv - _param_ekf2_magbias_x . get ( ) ,
_mag_data_sum [ 1 ] * mag_sample_count_inv - _param_ekf2_magbias_y . get ( ) ,
_mag_data_sum [ 2 ] * mag_sample_count_inv - _param_ekf2_magbias_z . get ( )
2017-03-30 09:21:47 +11:00
} ;
2017-11-07 15:55:50 -05:00
2016-11-07 09:20:30 +11:00
_ekf . setMagData ( 1000 * ( uint64_t ) mag_time_ms , mag_data_avg_ga ) ;
2017-11-07 15:55:50 -05:00
2016-11-06 17:10:44 +11:00
_mag_time_ms_last_used = mag_time_ms ;
_mag_time_sum_ms = 0 ;
_mag_sample_count = 0 ;
_mag_data_sum [ 0 ] = 0.0f ;
_mag_data_sum [ 1 ] = 0.0f ;
_mag_data_sum [ 2 ] = 0.0f ;
}
2018-03-19 14:17:16 -04:00
ekf2_timestamps . vehicle_magnetometer_timestamp_rel = ( int16_t ) ( ( int64_t ) magnetometer . timestamp / 100 -
( int64_t ) ekf2_timestamps . timestamp / 100 ) ;
2016-11-06 17:10:44 +11:00
}
2016-06-25 15:57:03 +02:00
}
2015-11-26 23:53:29 +01:00
// read baro data
2019-05-30 11:46:37 -04:00
if ( _airdata_sub . updated ( ) ) {
2018-02-18 11:44:21 -05:00
vehicle_air_data_s airdata ;
2016-08-05 22:26:02 -04:00
2019-05-30 11:46:37 -04:00
if ( _airdata_sub . copy ( & airdata ) ) {
2016-11-07 10:56:43 +11:00
// If the time last used by the EKF is less than specified, then accumulate the
2017-04-22 08:15:59 +10:00
// data and push the average when the specified interval is reached.
2018-02-18 11:44:21 -05:00
_balt_time_sum_ms + = airdata . timestamp / 1000 ;
2016-11-07 08:08:17 +11:00
_balt_sample_count + + ;
2018-02-18 11:44:21 -05:00
_balt_data_sum + = airdata . baro_alt_meter ;
2016-11-07 10:56:43 +11:00
uint32_t balt_time_ms = _balt_time_sum_ms / _balt_sample_count ;
2016-11-07 09:20:30 +11:00
2016-11-07 10:56:43 +11:00
if ( balt_time_ms - _balt_time_ms_last_used > ( uint32_t ) _params - > sensor_interval_min_ms ) {
2017-08-01 07:29:08 +10:00
// take mean across sample period
2016-11-07 08:08:17 +11:00
float balt_data_avg = _balt_data_sum / ( float ) _balt_sample_count ;
2017-08-01 07:29:08 +10:00
2018-02-18 11:44:21 -05:00
_ekf . set_air_density ( airdata . rho ) ;
2017-08-01 07:29:08 +10:00
// calculate static pressure error = Pmeas - Ptruth
2019-02-27 15:14:44 +11:00
// model position error sensitivity as a body fixed ellipse with a different scale in the positive and
2019-02-27 09:11:40 +11:00
// negative X and Y directions
2018-03-14 13:46:19 -04:00
const Vector3f vel_body_wind = get_vel_body_wind ( ) ;
2019-02-27 09:11:40 +11:00
float K_pstatic_coef_x ;
2019-02-27 15:14:44 +11:00
2018-03-14 13:46:19 -04:00
if ( vel_body_wind ( 0 ) > = 0.0f ) {
2019-03-26 10:44:53 +01:00
K_pstatic_coef_x = _param_ekf2_pcoef_xp . get ( ) ;
2017-08-01 07:29:08 +10:00
} else {
2019-03-26 10:44:53 +01:00
K_pstatic_coef_x = _param_ekf2_pcoef_xn . get ( ) ;
2017-08-01 07:29:08 +10:00
}
2019-02-27 09:11:40 +11:00
float K_pstatic_coef_y ;
2019-02-27 15:14:44 +11:00
2019-02-27 09:11:40 +11:00
if ( vel_body_wind ( 1 ) > = 0.0f ) {
2019-03-26 10:44:53 +01:00
K_pstatic_coef_y = _param_ekf2_pcoef_yp . get ( ) ;
2019-02-27 09:11:40 +11:00
} else {
2019-03-26 10:44:53 +01:00
K_pstatic_coef_y = _param_ekf2_pcoef_yn . get ( ) ;
2019-02-27 09:11:40 +11:00
}
2019-03-26 10:44:53 +01:00
const float max_airspeed_sq = _param_ekf2_aspd_max . get ( ) * _param_ekf2_aspd_max . get ( ) ;
2018-03-14 13:46:19 -04:00
const float x_v2 = fminf ( vel_body_wind ( 0 ) * vel_body_wind ( 0 ) , max_airspeed_sq ) ;
const float y_v2 = fminf ( vel_body_wind ( 1 ) * vel_body_wind ( 1 ) , max_airspeed_sq ) ;
const float z_v2 = fminf ( vel_body_wind ( 2 ) * vel_body_wind ( 2 ) , max_airspeed_sq ) ;
2019-06-26 09:37:25 +02:00
const float pstatic_err = 0.5f * airdata . rho * (
K_pstatic_coef_x * x_v2 + K_pstatic_coef_y * y_v2 + _param_ekf2_pcoef_z . get ( ) * z_v2 ) ;
2017-08-01 07:29:08 +10:00
// correct baro measurement using pressure error estimate and assuming sea level gravity
2018-02-18 11:44:21 -05:00
balt_data_avg + = pstatic_err / ( airdata . rho * CONSTANTS_ONE_G ) ;
2017-08-01 07:29:08 +10:00
// push to estimator
2017-01-15 10:19:05 +01:00
_ekf . setBaroData ( 1000 * ( uint64_t ) balt_time_ms , balt_data_avg ) ;
2017-11-07 15:55:50 -05:00
2016-11-07 08:08:17 +11:00
_balt_time_ms_last_used = balt_time_ms ;
_balt_time_sum_ms = 0 ;
_balt_sample_count = 0 ;
_balt_data_sum = 0.0f ;
}
2018-03-19 14:17:16 -04:00
ekf2_timestamps . vehicle_air_data_timestamp_rel = ( int16_t ) ( ( int64_t ) airdata . timestamp / 100 -
( int64_t ) ekf2_timestamps . timestamp / 100 ) ;
2016-11-06 17:10:44 +11:00
}
2016-06-25 15:57:03 +02:00
}
2015-11-26 23:53:29 +01:00
2018-07-23 02:18:30 +10:00
// read gps1 data if available
2019-05-30 11:46:37 -04:00
bool gps1_updated = _gps_subs [ 0 ] . updated ( ) ;
2018-03-19 14:17:16 -04:00
2018-07-23 02:18:30 +10:00
if ( gps1_updated ) {
2018-03-19 14:17:16 -04:00
vehicle_gps_position_s gps ;
2019-05-30 11:46:37 -04:00
if ( _gps_subs [ 0 ] . copy ( & gps ) ) {
2018-07-23 02:18:30 +10:00
_gps_state [ 0 ] . time_usec = gps . timestamp ;
_gps_state [ 0 ] . lat = gps . lat ;
_gps_state [ 0 ] . lon = gps . lon ;
_gps_state [ 0 ] . alt = gps . alt ;
2018-08-16 14:40:41 +10:00
_gps_state [ 0 ] . yaw = gps . heading ;
_gps_state [ 0 ] . yaw_offset = gps . heading_offset ;
2018-07-23 02:18:30 +10:00
_gps_state [ 0 ] . fix_type = gps . fix_type ;
_gps_state [ 0 ] . eph = gps . eph ;
_gps_state [ 0 ] . epv = gps . epv ;
_gps_state [ 0 ] . sacc = gps . s_variance_m_s ;
_gps_state [ 0 ] . vel_m_s = gps . vel_m_s ;
_gps_state [ 0 ] . vel_ned [ 0 ] = gps . vel_n_m_s ;
_gps_state [ 0 ] . vel_ned [ 1 ] = gps . vel_e_m_s ;
_gps_state [ 0 ] . vel_ned [ 2 ] = gps . vel_d_m_s ;
_gps_state [ 0 ] . vel_ned_valid = gps . vel_ned_valid ;
_gps_state [ 0 ] . nsats = gps . satellites_used ;
2018-03-19 14:17:16 -04:00
//TODO: add gdop to gps topic
2018-07-23 02:18:30 +10:00
_gps_state [ 0 ] . gdop = 0.0f ;
2018-09-07 10:42:29 +02:00
_gps_alttitude_ellipsoid [ 0 ] = gps . alt_ellipsoid ;
2018-03-19 14:17:16 -04:00
ekf2_timestamps . gps_timestamp_rel = ( int16_t ) ( ( int64_t ) gps . timestamp / 100 - ( int64_t ) ekf2_timestamps . timestamp / 100 ) ;
}
2015-11-26 23:53:29 +01:00
}
2018-07-23 02:18:30 +10:00
// check for second GPS receiver data
2019-05-30 11:46:37 -04:00
bool gps2_updated = _gps_subs [ 1 ] . updated ( ) ;
2018-07-23 02:18:30 +10:00
if ( gps2_updated ) {
vehicle_gps_position_s gps ;
2019-05-30 11:46:37 -04:00
if ( _gps_subs [ 1 ] . copy ( & gps ) ) {
2018-07-23 02:18:30 +10:00
_gps_state [ 1 ] . time_usec = gps . timestamp ;
_gps_state [ 1 ] . lat = gps . lat ;
_gps_state [ 1 ] . lon = gps . lon ;
_gps_state [ 1 ] . alt = gps . alt ;
2018-08-16 14:40:41 +10:00
_gps_state [ 1 ] . yaw = gps . heading ;
_gps_state [ 1 ] . yaw_offset = gps . heading_offset ;
2018-07-23 02:18:30 +10:00
_gps_state [ 1 ] . fix_type = gps . fix_type ;
_gps_state [ 1 ] . eph = gps . eph ;
_gps_state [ 1 ] . epv = gps . epv ;
_gps_state [ 1 ] . sacc = gps . s_variance_m_s ;
_gps_state [ 1 ] . vel_m_s = gps . vel_m_s ;
_gps_state [ 1 ] . vel_ned [ 0 ] = gps . vel_n_m_s ;
_gps_state [ 1 ] . vel_ned [ 1 ] = gps . vel_e_m_s ;
_gps_state [ 1 ] . vel_ned [ 2 ] = gps . vel_d_m_s ;
_gps_state [ 1 ] . vel_ned_valid = gps . vel_ned_valid ;
_gps_state [ 1 ] . nsats = gps . satellites_used ;
//TODO: add gdop to gps topic
_gps_state [ 1 ] . gdop = 0.0f ;
2018-09-07 10:42:29 +02:00
_gps_alttitude_ellipsoid [ 1 ] = gps . alt_ellipsoid ;
2018-07-23 02:18:30 +10:00
}
}
2019-03-26 10:44:53 +01:00
if ( ( _param_ekf2_gps_mask . get ( ) = = 0 ) & & gps1_updated ) {
2018-07-23 02:18:30 +10:00
// When GPS blending is disabled we always use the first receiver instance
2019-03-05 23:28:26 -05:00
_ekf . setGpsData ( _gps_state [ 0 ] . time_usec , _gps_state [ 0 ] ) ;
2018-07-23 02:18:30 +10:00
2019-03-26 10:44:53 +01:00
} else if ( ( _param_ekf2_gps_mask . get ( ) > 0 ) & & ( gps1_updated | | gps2_updated ) ) {
2018-07-23 02:18:30 +10:00
// blend dual receivers if available
// calculate blending weights
2018-09-29 23:23:19 +10:00
if ( ! blend_gps_data ( ) ) {
2018-07-23 02:18:30 +10:00
// handle case where the blended states cannot be updated
2018-08-01 14:19:51 -04:00
if ( _gps_state [ 0 ] . fix_type > _gps_state [ 1 ] . fix_type ) {
2018-07-23 02:18:30 +10:00
// GPS 1 has the best fix status so use that
_gps_select_index = 0 ;
} else if ( _gps_state [ 1 ] . fix_type > _gps_state [ 0 ] . fix_type ) {
// GPS 2 has the best fix status so use that
_gps_select_index = 1 ;
} else if ( _gps_select_index = = 2 ) {
// use last receiver we received data from
if ( gps1_updated ) {
_gps_select_index = 0 ;
} else if ( gps2_updated ) {
_gps_select_index = 1 ;
}
}
2018-09-29 23:23:19 +10:00
// Only use selected receiver data if it has been updated
if ( ( gps1_updated & & _gps_select_index = = 0 ) | | ( gps2_updated & & _gps_select_index = = 1 ) ) {
_gps_new_output_data = true ;
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
} else {
_gps_new_output_data = false ;
}
2018-07-23 02:18:30 +10:00
}
2018-09-29 23:23:19 +10:00
if ( _gps_new_output_data ) {
// correct the _gps_state data for steady state offsets and write to _gps_output
apply_gps_offsets ( ) ;
// calculate a blended output from the offset corrected receiver data
if ( _gps_select_index = = 2 ) {
calc_gps_blend_output ( ) ;
}
// write selected GPS to EKF
2019-03-05 23:28:26 -05:00
_ekf . setGpsData ( _gps_output [ _gps_select_index ] . time_usec , _gps_output [ _gps_select_index ] ) ;
2018-09-29 23:23:19 +10:00
// log blended solution as a third GPS instance
ekf_gps_position_s gps ;
gps . timestamp = _gps_output [ _gps_select_index ] . time_usec ;
gps . lat = _gps_output [ _gps_select_index ] . lat ;
gps . lon = _gps_output [ _gps_select_index ] . lon ;
gps . alt = _gps_output [ _gps_select_index ] . alt ;
gps . fix_type = _gps_output [ _gps_select_index ] . fix_type ;
gps . eph = _gps_output [ _gps_select_index ] . eph ;
gps . epv = _gps_output [ _gps_select_index ] . epv ;
gps . s_variance_m_s = _gps_output [ _gps_select_index ] . sacc ;
gps . vel_m_s = _gps_output [ _gps_select_index ] . vel_m_s ;
gps . vel_n_m_s = _gps_output [ _gps_select_index ] . vel_ned [ 0 ] ;
gps . vel_e_m_s = _gps_output [ _gps_select_index ] . vel_ned [ 1 ] ;
gps . vel_d_m_s = _gps_output [ _gps_select_index ] . vel_ned [ 2 ] ;
gps . vel_ned_valid = _gps_output [ _gps_select_index ] . vel_ned_valid ;
gps . satellites_used = _gps_output [ _gps_select_index ] . nsats ;
2018-08-16 14:40:41 +10:00
gps . heading = _gps_output [ _gps_select_index ] . yaw ;
gps . heading_offset = _gps_output [ _gps_select_index ] . yaw_offset ;
2018-09-29 23:23:19 +10:00
gps . selected = _gps_select_index ;
// Publish to the EKF blended GPS topic
2019-06-12 08:48:19 -04:00
_blended_gps_pub . publish ( gps ) ;
2018-09-29 23:23:19 +10:00
// clear flag to avoid re-use of the same data
_gps_new_output_data = false ;
}
2018-07-23 02:18:30 +10:00
}
2019-05-30 11:46:37 -04:00
if ( _airspeed_sub . updated ( ) ) {
2018-03-19 14:17:16 -04:00
airspeed_s airspeed ;
2015-12-06 13:24:42 +01:00
2019-05-30 11:46:37 -04:00
if ( _airspeed_sub . copy ( & airspeed ) ) {
2018-03-19 14:17:16 -04:00
// only set airspeed data if condition for airspeed fusion are met
2019-03-26 10:44:53 +01:00
if ( ( _param_ekf2_arsp_thr . get ( ) > FLT_EPSILON ) & & ( airspeed . true_airspeed_m_s > _param_ekf2_arsp_thr . get ( ) ) ) {
2018-03-19 14:17:16 -04:00
const float eas2tas = airspeed . true_airspeed_m_s / airspeed . indicated_airspeed_m_s ;
_ekf . setAirspeedData ( airspeed . timestamp , airspeed . true_airspeed_m_s , eas2tas ) ;
}
2016-06-08 19:57:44 +02:00
2018-03-19 14:17:16 -04:00
ekf2_timestamps . airspeed_timestamp_rel = ( int16_t ) ( ( int64_t ) airspeed . timestamp / 100 -
( int64_t ) ekf2_timestamps . timestamp / 100 ) ;
}
2017-09-05 12:56:53 -04:00
}
2017-07-29 07:18:58 +10:00
2019-05-30 11:46:37 -04:00
if ( _optical_flow_sub . updated ( ) ) {
2018-03-19 14:17:16 -04:00
optical_flow_s optical_flow ;
2019-05-30 11:46:37 -04:00
if ( _optical_flow_sub . copy ( & optical_flow ) ) {
2018-03-19 14:17:16 -04:00
flow_message flow ;
flow . flowdata ( 0 ) = optical_flow . pixel_flow_x_integral ;
flow . flowdata ( 1 ) = optical_flow . pixel_flow_y_integral ;
flow . quality = optical_flow . quality ;
flow . gyrodata ( 0 ) = optical_flow . gyro_x_rate_integral ;
flow . gyrodata ( 1 ) = optical_flow . gyro_y_rate_integral ;
flow . gyrodata ( 2 ) = optical_flow . gyro_z_rate_integral ;
flow . dt = optical_flow . integration_timespan ;
if ( PX4_ISFINITE ( optical_flow . pixel_flow_y_integral ) & &
PX4_ISFINITE ( optical_flow . pixel_flow_x_integral ) ) {
_ekf . setOpticalFlowData ( optical_flow . timestamp , & flow ) ;
}
2018-05-19 14:11:57 -04:00
// Save sensor limits reported by the optical flow sensor
2018-05-21 21:42:59 -04:00
_ekf . set_optical_flow_limits ( optical_flow . max_flow_rate , optical_flow . min_ground_distance ,
optical_flow . max_ground_distance ) ;
2018-05-19 14:11:57 -04:00
2018-03-19 14:17:16 -04:00
ekf2_timestamps . optical_flow_timestamp_rel = ( int16_t ) ( ( int64_t ) optical_flow . timestamp / 100 -
( int64_t ) ekf2_timestamps . timestamp / 100 ) ;
2016-02-17 11:45:45 -08:00
}
}
2018-04-11 22:33:34 -04:00
if ( _range_finder_sub_index > = 0 ) {
2018-03-19 14:17:16 -04:00
2019-09-19 11:29:34 +02:00
if ( _range_finder_subs [ _range_finder_sub_index ] . updated ( ) ) {
2018-03-19 14:17:16 -04:00
distance_sensor_s range_finder ;
2019-05-30 11:46:37 -04:00
if ( _range_finder_subs [ _range_finder_sub_index ] . copy ( & range_finder ) ) {
2019-09-19 11:29:34 +02:00
_ekf . setRangeData ( range_finder . timestamp , range_finder . current_distance , range_finder . signal_quality ) ;
2018-03-19 14:17:16 -04:00
2018-05-19 14:11:57 -04:00
// Save sensor limits reported by the rangefinder
_ekf . set_rangefinder_limits ( range_finder . min_distance , range_finder . max_distance ) ;
2018-03-19 14:17:16 -04:00
ekf2_timestamps . distance_sensor_timestamp_rel = ( int16_t ) ( ( int64_t ) range_finder . timestamp / 100 -
( int64_t ) ekf2_timestamps . timestamp / 100 ) ;
}
}
} else {
2019-05-30 11:46:37 -04:00
_range_finder_sub_index = getRangeSubIndex ( ) ;
2016-02-17 11:45:45 -08:00
}
2016-05-27 11:39:45 +10:00
// get external vision data
// if error estimates are unavailable, use parameter defined defaults
2019-09-23 20:24:52 +02:00
new_ev_data_received = false ;
2019-05-30 11:46:37 -04:00
if ( _ev_odom_sub . updated ( ) ) {
2019-09-23 20:24:52 +02:00
new_ev_data_received = true ;
2018-07-12 18:25:00 +01:00
// copy both attitude & position, we need both to fill a single ext_vision_message
2019-09-23 20:24:52 +02:00
_ev_odom_sub . copy ( & _ev_odom ) ;
2018-03-19 14:17:16 -04:00
2016-05-26 23:29:19 +10:00
ext_vision_message ev_data ;
2018-07-26 15:53:46 +01:00
2019-09-26 10:21:53 +02:00
// check for valid velocity data
if ( PX4_ISFINITE ( _ev_odom . vx ) & & PX4_ISFINITE ( _ev_odom . vy ) & & PX4_ISFINITE ( _ev_odom . vz ) ) {
ev_data . vel ( 0 ) = _ev_odom . vx ;
ev_data . vel ( 1 ) = _ev_odom . vy ;
ev_data . vel ( 2 ) = _ev_odom . vz ;
// velocity measurement error from parameters
if ( PX4_ISFINITE ( _ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_X_VARIANCE ] ) ) {
ev_data . velErr = fmaxf ( _param_ekf2_evv_noise . get ( ) ,
sqrtf ( fmaxf ( _ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_VX_VARIANCE ] ,
fmaxf ( _ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_VY_VARIANCE ] ,
_ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_VZ_VARIANCE ] ) ) ) ) ;
} else {
ev_data . velErr = _param_ekf2_evv_noise . get ( ) ;
}
}
2018-07-26 15:53:46 +01:00
// check for valid position data
2019-09-23 20:24:52 +02:00
if ( PX4_ISFINITE ( _ev_odom . x ) & & PX4_ISFINITE ( _ev_odom . y ) & & PX4_ISFINITE ( _ev_odom . z ) ) {
2019-09-26 10:21:53 +02:00
ev_data . pos ( 0 ) = _ev_odom . x ;
ev_data . pos ( 1 ) = _ev_odom . y ;
ev_data . pos ( 2 ) = _ev_odom . z ;
2018-07-26 15:53:46 +01:00
2019-09-23 20:24:52 +02:00
// position measurement error from parameter
if ( PX4_ISFINITE ( _ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_X_VARIANCE ] ) ) {
2019-03-26 10:44:53 +01:00
ev_data . posErr = fmaxf ( _param_ekf2_evp_noise . get ( ) ,
2019-09-23 20:24:52 +02:00
sqrtf ( fmaxf ( _ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_X_VARIANCE ] ,
_ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_Y_VARIANCE ] ) ) ) ;
2019-03-26 10:44:53 +01:00
ev_data . hgtErr = fmaxf ( _param_ekf2_evp_noise . get ( ) ,
2019-09-23 20:24:52 +02:00
sqrtf ( _ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_Z_VARIANCE ] ) ) ;
2018-09-17 14:23:25 +01:00
2018-07-26 15:53:46 +01:00
} else {
2019-03-26 10:44:53 +01:00
ev_data . posErr = _param_ekf2_evp_noise . get ( ) ;
ev_data . hgtErr = _param_ekf2_evp_noise . get ( ) ;
2018-07-26 15:53:46 +01:00
}
2018-07-12 18:25:00 +01:00
}
2018-07-12 20:45:59 +01:00
2018-07-26 15:53:46 +01:00
// check for valid orientation data
2019-09-23 20:24:52 +02:00
if ( PX4_ISFINITE ( _ev_odom . q [ 0 ] ) ) {
ev_data . quat = matrix : : Quatf ( _ev_odom . q ) ;
2018-07-12 20:45:59 +01:00
2018-07-26 15:53:46 +01:00
// orientation measurement error from parameters
2019-09-23 20:24:52 +02:00
if ( PX4_ISFINITE ( _ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_ROLL_VARIANCE ] ) ) {
2019-03-26 10:44:53 +01:00
ev_data . angErr = fmaxf ( _param_ekf2_eva_noise . get ( ) ,
2019-09-23 20:24:52 +02:00
sqrtf ( _ev_odom . pose_covariance [ _ev_odom . COVARIANCE_MATRIX_YAW_VARIANCE ] ) ) ;
2018-07-26 15:53:46 +01:00
} else {
2019-03-26 10:44:53 +01:00
ev_data . angErr = _param_ekf2_eva_noise . get ( ) ;
2018-07-26 15:53:46 +01:00
}
2018-07-12 18:25:00 +01:00
}
2018-07-26 15:53:46 +01:00
// only set data if all positions and orientation are valid
if ( ev_data . posErr < ep_max_std_dev & & ev_data . angErr < eo_max_std_dev ) {
2018-01-09 18:46:07 +01:00
// use timestamp from external computer, clocks are synchronized when using MAVROS
2019-09-23 20:24:52 +02:00
_ekf . setExtVisionData ( _ev_odom . timestamp , & ev_data ) ;
2018-01-09 18:46:07 +01:00
}
2018-03-19 14:17:16 -04:00
2019-09-23 20:24:52 +02:00
ekf2_timestamps . visual_odometry_timestamp_rel = ( int16_t ) ( ( int64_t ) _ev_odom . timestamp / 100 -
2018-03-19 14:17:16 -04:00
( int64_t ) ekf2_timestamps . timestamp / 100 ) ;
2016-05-26 23:29:19 +10:00
}
2019-05-30 11:46:37 -04:00
bool vehicle_land_detected_updated = _vehicle_land_detected_sub . updated ( ) ;
2016-02-25 17:00:39 +00:00
if ( vehicle_land_detected_updated ) {
2019-05-30 11:46:37 -04:00
if ( _vehicle_land_detected_sub . copy ( & vehicle_land_detected ) ) {
2018-03-19 14:17:16 -04:00
_ekf . set_in_air_status ( ! vehicle_land_detected . landed ) ;
}
2016-02-13 08:56:25 +01:00
}
2018-01-14 23:22:38 +05:30
// use the landing target pose estimate as another source of velocity data
2019-05-30 11:46:37 -04:00
if ( _landing_target_pose_sub . updated ( ) ) {
2018-04-11 22:33:34 -04:00
landing_target_pose_s landing_target_pose ;
2019-05-30 11:46:37 -04:00
if ( _landing_target_pose_sub . copy ( & landing_target_pose ) ) {
2018-04-11 22:33:34 -04:00
// we can only use the landing target if it has a fixed position and a valid velocity estimate
if ( landing_target_pose . is_static & & landing_target_pose . rel_vel_valid ) {
// velocity of vehicle relative to target has opposite sign to target relative to vehicle
2019-03-08 18:12:58 +03:00
float velocity [ 2 ] = { - landing_target_pose . vx_rel , - landing_target_pose . vy_rel } ;
2018-04-11 22:33:34 -04:00
float variance [ 2 ] = { landing_target_pose . cov_vx_rel , landing_target_pose . cov_vy_rel } ;
_ekf . setAuxVelData ( landing_target_pose . timestamp , velocity , variance ) ;
}
2018-01-14 23:22:38 +05:30
}
}
2018-06-28 17:28:03 -04:00
perf_end ( _perf_update_data ) ;
2016-03-16 14:22:06 +11:00
// run the EKF update and output
2018-06-28 17:28:03 -04:00
perf_begin ( _perf_ekf_update ) ;
2017-11-07 15:55:50 -05:00
const bool updated = _ekf . update ( ) ;
2018-06-28 17:28:03 -04:00
perf_end ( _perf_ekf_update ) ;
2017-11-07 15:55:50 -05:00
2018-07-08 18:11:24 -04:00
// integrate time to monitor time slippage
if ( _start_time_us = = 0 ) {
_start_time_us = now ;
_last_time_slip_us = 0 ;
2015-12-23 11:40:25 +01:00
2018-07-08 18:11:24 -04:00
} else if ( _start_time_us > 0 ) {
_integrated_time_us + = sensors . gyro_integral_dt ;
_last_time_slip_us = ( now - _start_time_us ) - _integrated_time_us ;
}
2016-01-09 10:51:09 +01:00
2018-07-08 18:11:24 -04:00
if ( updated ) {
2016-03-16 14:22:06 +11:00
2018-07-08 18:11:24 -04:00
filter_control_status_u control_status ;
_ekf . get_control_mode ( & control_status . value ) ;
// only publish position after successful alignment
if ( control_status . flags . tilt_align ) {
// generate vehicle local position data
vehicle_local_position_s & lpos = _vehicle_local_position_pub . get ( ) ;
2018-12-21 17:54:04 +00:00
// generate vehicle odometry data
2019-06-12 08:48:19 -04:00
vehicle_odometry_s odom { } ;
2018-12-21 17:54:04 +00:00
2018-07-08 18:11:24 -04:00
lpos . timestamp = now ;
2018-12-21 17:54:04 +00:00
odom . timestamp = lpos . timestamp ;
odom . local_frame = odom . LOCAL_FRAME_NED ;
2018-07-08 18:11:24 -04:00
// Position of body origin in local NED frame
float position [ 3 ] ;
_ekf . get_position ( position ) ;
const float lpos_x_prev = lpos . x ;
const float lpos_y_prev = lpos . y ;
lpos . x = ( _ekf . local_position_is_valid ( ) ) ? position [ 0 ] : 0.0f ;
lpos . y = ( _ekf . local_position_is_valid ( ) ) ? position [ 1 ] : 0.0f ;
lpos . z = position [ 2 ] ;
2018-12-21 17:54:04 +00:00
// Vehicle odometry position
odom . x = lpos . x ;
odom . y = lpos . y ;
odom . z = lpos . z ;
2018-07-08 18:11:24 -04:00
// Velocity of body origin in local NED frame (m/s)
float velocity [ 3 ] ;
_ekf . get_velocity ( velocity ) ;
lpos . vx = velocity [ 0 ] ;
lpos . vy = velocity [ 1 ] ;
lpos . vz = velocity [ 2 ] ;
2018-12-21 17:54:04 +00:00
// Vehicle odometry linear velocity
odom . vx = lpos . vx ;
odom . vy = lpos . vy ;
odom . vz = lpos . vz ;
2018-07-08 18:11:24 -04:00
// vertical position time derivative (m/s)
_ekf . get_pos_d_deriv ( & lpos . z_deriv ) ;
// Acceleration of body origin in local NED frame
float vel_deriv [ 3 ] ;
_ekf . get_vel_deriv_ned ( vel_deriv ) ;
lpos . ax = vel_deriv [ 0 ] ;
lpos . ay = vel_deriv [ 1 ] ;
lpos . az = vel_deriv [ 2 ] ;
// TODO: better status reporting
lpos . xy_valid = _ekf . local_position_is_valid ( ) & & ! _preflt_horiz_fail ;
lpos . z_valid = ! _preflt_vert_fail ;
lpos . v_xy_valid = _ekf . local_position_is_valid ( ) & & ! _preflt_horiz_fail ;
lpos . v_z_valid = ! _preflt_vert_fail ;
// Position of local NED origin in GPS / WGS84 frame
map_projection_reference_s ekf_origin ;
uint64_t origin_time ;
// true if position (x,y,z) has a valid WGS-84 global reference (ref_lat, ref_lon, alt)
const bool ekf_origin_valid = _ekf . get_ekf_origin ( & origin_time , & ekf_origin , & lpos . ref_alt ) ;
lpos . xy_global = ekf_origin_valid ;
lpos . z_global = ekf_origin_valid ;
if ( ekf_origin_valid & & ( origin_time > lpos . ref_timestamp ) ) {
lpos . ref_timestamp = origin_time ;
lpos . ref_lat = ekf_origin . lat_rad * 180.0 / M_PI ; // Reference point latitude in degrees
lpos . ref_lon = ekf_origin . lon_rad * 180.0 / M_PI ; // Reference point longitude in degrees
2016-11-01 12:45:36 +01:00
}
2016-03-16 14:22:06 +11:00
2018-07-08 18:11:24 -04:00
// The rotation of the tangent plane vs. geographical north
2019-09-16 11:12:23 +02:00
matrix : : Quatf q = _ekf . get_quaternion ( ) ;
2018-07-12 18:25:00 +01:00
lpos . yaw = matrix : : Eulerf ( q ) . psi ( ) ;
2016-03-16 14:22:06 +11:00
2018-12-21 17:54:04 +00:00
// Vehicle odometry quaternion
q . copyTo ( odom . q ) ;
// Vehicle odometry angular rates
float gyro_bias [ 3 ] ;
_ekf . get_gyro_bias ( gyro_bias ) ;
odom . rollspeed = sensors . gyro_rad [ 0 ] - gyro_bias [ 0 ] ;
odom . pitchspeed = sensors . gyro_rad [ 1 ] - gyro_bias [ 1 ] ;
odom . yawspeed = sensors . gyro_rad [ 2 ] - gyro_bias [ 2 ] ;
2018-07-08 18:11:24 -04:00
lpos . dist_bottom_valid = _ekf . get_terrain_valid ( ) ;
2016-03-16 14:22:06 +11:00
2018-07-08 18:11:24 -04:00
float terrain_vpos ;
_ekf . get_terrain_vert_pos ( & terrain_vpos ) ;
lpos . dist_bottom = terrain_vpos - lpos . z ; // Distance to bottom surface (ground) in meters
2017-09-21 16:24:53 -04:00
2018-07-08 18:11:24 -04:00
// constrain the distance to ground to _rng_gnd_clearance
2019-03-26 10:44:53 +01:00
if ( lpos . dist_bottom < _param_ekf2_min_rng . get ( ) ) {
lpos . dist_bottom = _param_ekf2_min_rng . get ( ) ;
2018-07-08 18:11:24 -04:00
}
2017-07-21 23:49:00 +02:00
2019-04-26 21:33:36 +02:00
if ( ! _had_valid_terrain ) {
_had_valid_terrain = lpos . dist_bottom_valid ;
2019-03-11 14:44:01 +03:00
}
2019-04-29 15:12:07 +02:00
// only consider ground effect if compensation is configured and the vehicle is armed (props spinning)
if ( _param_ekf2_gnd_eff_dz . get ( ) > 0.0f & & vehicle_status . arming_state = = vehicle_status_s : : ARMING_STATE_ARMED ) {
2019-04-26 21:33:36 +02:00
// set ground effect flag if vehicle is closer than a specified distance to the ground
if ( lpos . dist_bottom_valid ) {
_ekf . set_gnd_effect_flag ( lpos . dist_bottom < _param_ekf2_gnd_max_hgt . get ( ) ) ;
// if we have no valid terrain estimate and never had one then use ground effect flag from land detector
// _had_valid_terrain is used to make sure that we don't fall back to using this option
// if we temporarily lose terrain data due to the distance sensor getting out of range
2019-04-29 15:12:07 +02:00
} else if ( vehicle_land_detected_updated & & ! _had_valid_terrain ) {
2019-04-26 21:33:36 +02:00
// update ground effect flag based on land detector state
_ekf . set_gnd_effect_flag ( vehicle_land_detected . in_ground_effect ) ;
}
} else {
_ekf . set_gnd_effect_flag ( false ) ;
2019-03-11 14:51:02 +03:00
}
2018-07-08 18:11:24 -04:00
lpos . dist_bottom_rate = - lpos . vz ; // Distance to bottom surface (ground) change rate
2017-07-21 23:49:00 +02:00
2018-07-08 18:11:24 -04:00
_ekf . get_ekf_lpos_accuracy ( & lpos . eph , & lpos . epv ) ;
_ekf . get_ekf_vel_accuracy ( & lpos . evh , & lpos . evv ) ;
2016-03-16 14:22:06 +11:00
2018-07-08 18:11:24 -04:00
// get state reset information of position and velocity
_ekf . get_posD_reset ( & lpos . delta_z , & lpos . z_reset_counter ) ;
_ekf . get_velD_reset ( & lpos . delta_vz , & lpos . vz_reset_counter ) ;
_ekf . get_posNE_reset ( & lpos . delta_xy [ 0 ] , & lpos . xy_reset_counter ) ;
_ekf . get_velNE_reset ( & lpos . delta_vxy [ 0 ] , & lpos . vxy_reset_counter ) ;
2016-03-16 14:22:06 +11:00
2018-07-08 18:11:24 -04:00
// get control limit information
_ekf . get_ekf_ctrl_limits ( & lpos . vxy_max , & lpos . vz_max , & lpos . hagl_min , & lpos . hagl_max ) ;
2016-06-06 13:34:39 +02:00
2018-07-08 18:11:24 -04:00
// convert NaN to INFINITY
if ( ! PX4_ISFINITE ( lpos . vxy_max ) ) {
lpos . vxy_max = INFINITY ;
}
2017-09-19 10:03:59 +10:00
2018-07-08 18:11:24 -04:00
if ( ! PX4_ISFINITE ( lpos . vz_max ) ) {
lpos . vz_max = INFINITY ;
}
2018-05-21 21:42:59 -04:00
2018-07-08 18:11:24 -04:00
if ( ! PX4_ISFINITE ( lpos . hagl_min ) ) {
lpos . hagl_min = INFINITY ;
}
2018-05-21 21:42:59 -04:00
2018-07-08 18:11:24 -04:00
if ( ! PX4_ISFINITE ( lpos . hagl_max ) ) {
lpos . hagl_max = INFINITY ;
}
2018-05-21 21:42:59 -04:00
2018-12-21 17:54:04 +00:00
// Get covariances to vehicle odometry
float covariances [ 24 ] ;
2019-03-13 08:26:31 +11:00
_ekf . covariances_diagonal ( ) . copyTo ( covariances ) ;
2018-12-21 17:54:04 +00:00
// get the covariance matrix size
const size_t POS_URT_SIZE = sizeof ( odom . pose_covariance ) / sizeof ( odom . pose_covariance [ 0 ] ) ;
const size_t VEL_URT_SIZE = sizeof ( odom . velocity_covariance ) / sizeof ( odom . velocity_covariance [ 0 ] ) ;
// initially set pose covariances to 0
for ( size_t i = 0 ; i < POS_URT_SIZE ; i + + ) {
odom . pose_covariance [ i ] = 0.0 ;
}
// set the position variances
odom . pose_covariance [ odom . COVARIANCE_MATRIX_X_VARIANCE ] = covariances [ 7 ] ;
odom . pose_covariance [ odom . COVARIANCE_MATRIX_Y_VARIANCE ] = covariances [ 8 ] ;
odom . pose_covariance [ odom . COVARIANCE_MATRIX_Z_VARIANCE ] = covariances [ 9 ] ;
// TODO: implement propagation from quaternion covariance to Euler angle covariance
// by employing the covariance law
// initially set velocity covariances to 0
for ( size_t i = 0 ; i < VEL_URT_SIZE ; i + + ) {
odom . velocity_covariance [ i ] = 0.0 ;
}
// set the linear velocity variances
odom . velocity_covariance [ odom . COVARIANCE_MATRIX_VX_VARIANCE ] = covariances [ 4 ] ;
odom . velocity_covariance [ odom . COVARIANCE_MATRIX_VY_VARIANCE ] = covariances [ 5 ] ;
odom . velocity_covariance [ odom . COVARIANCE_MATRIX_VZ_VARIANCE ] = covariances [ 6 ] ;
2018-07-08 18:11:24 -04:00
// publish vehicle local position data
_vehicle_local_position_pub . update ( ) ;
2017-09-19 10:03:59 +10:00
2018-12-21 17:54:04 +00:00
// publish vehicle odometry data
2019-06-12 08:48:19 -04:00
_vehicle_odometry_pub . publish ( odom ) ;
2018-12-21 17:54:04 +00:00
2019-09-23 20:24:52 +02:00
// publish external visual odometry after fixed frame alignment if new odometry is received
if ( new_ev_data_received ) {
float q_ev2ekf [ 4 ] ;
_ekf . get_ev2ekf_quaternion ( q_ev2ekf ) ; // rotates from EV to EKF navigation frame
Quatf quat_ev2ekf ( q_ev2ekf ) ;
Dcmf ev_rot_mat ( quat_ev2ekf ) ;
vehicle_odometry_s aligned_ev_odom = _ev_odom ;
// Rotate external position and velocity into EKF navigation frame
Vector3f aligned_pos = ev_rot_mat * Vector3f ( _ev_odom . x , _ev_odom . y , _ev_odom . z ) ;
aligned_ev_odom . x = aligned_pos ( 0 ) ;
aligned_ev_odom . y = aligned_pos ( 1 ) ;
aligned_ev_odom . z = aligned_pos ( 2 ) ;
Vector3f aligned_vel = ev_rot_mat * Vector3f ( _ev_odom . vx , _ev_odom . vy , _ev_odom . vz ) ;
aligned_ev_odom . vx = aligned_vel ( 0 ) ;
aligned_ev_odom . vy = aligned_vel ( 1 ) ;
aligned_ev_odom . vz = aligned_vel ( 2 ) ;
// Compute orientation in EKF navigation frame
Quatf ev_quat_aligned = quat_ev2ekf * matrix : : Quatf ( _ev_odom . q ) ;
ev_quat_aligned . normalize ( ) ;
ev_quat_aligned . copyTo ( aligned_ev_odom . q ) ;
quat_ev2ekf . copyTo ( aligned_ev_odom . q_offset ) ;
_vehicle_visual_odometry_aligned_pub . publish ( aligned_ev_odom ) ;
}
2018-07-08 18:11:24 -04:00
if ( _ekf . global_position_is_valid ( ) & & ! _preflt_fail ) {
// generate and publish global position data
vehicle_global_position_s & global_pos = _vehicle_global_position_pub . get ( ) ;
2015-12-31 18:37:16 +11:00
2018-07-08 18:11:24 -04:00
global_pos . timestamp = now ;
2016-11-01 09:08:02 +01:00
2018-07-08 18:11:24 -04:00
if ( fabsf ( lpos_x_prev - lpos . x ) > FLT_EPSILON | | fabsf ( lpos_y_prev - lpos . y ) > FLT_EPSILON ) {
map_projection_reproject ( & ekf_origin , lpos . x , lpos . y , & global_pos . lat , & global_pos . lon ) ;
}
2015-12-31 18:37:16 +11:00
2018-07-08 18:11:24 -04:00
global_pos . lat_lon_reset_counter = lpos . xy_reset_counter ;
2017-09-05 12:56:53 -04:00
2018-07-08 18:11:24 -04:00
global_pos . alt = - lpos . z + lpos . ref_alt ; // Altitude AMSL in meters
2018-09-07 10:42:29 +02:00
global_pos . alt_ellipsoid = filter_altitude_ellipsoid ( global_pos . alt ) ;
2015-12-10 16:38:51 +01:00
2018-07-08 18:11:24 -04:00
// global altitude has opposite sign of local down position
global_pos . delta_alt = - lpos . delta_z ;
2017-11-07 15:55:50 -05:00
2018-07-08 18:11:24 -04:00
global_pos . vel_n = lpos . vx ; // Ground north velocity, m/s
global_pos . vel_e = lpos . vy ; // Ground east velocity, m/s
global_pos . vel_d = lpos . vz ; // Ground downside velocity, m/s
2015-12-10 16:38:51 +01:00
2018-07-08 18:11:24 -04:00
global_pos . yaw = lpos . yaw ; // Yaw in radians -PI..+PI.
2015-12-31 18:37:16 +11:00
2018-07-08 18:11:24 -04:00
_ekf . get_ekf_gpos_accuracy ( & global_pos . eph , & global_pos . epv ) ;
2015-12-31 18:37:16 +11:00
2018-07-08 18:11:24 -04:00
global_pos . terrain_alt_valid = lpos . dist_bottom_valid ;
2018-04-19 07:19:39 +10:00
2018-07-08 18:11:24 -04:00
if ( global_pos . terrain_alt_valid ) {
global_pos . terrain_alt = lpos . ref_alt - terrain_vpos ; // Terrain altitude in m, WGS84
2015-12-31 18:37:16 +11:00
2018-07-08 18:11:24 -04:00
} else {
global_pos . terrain_alt = 0.0f ; // Terrain altitude in m, WGS84
}
2017-09-21 16:24:53 -04:00
2018-07-08 18:11:24 -04:00
global_pos . dead_reckoning = _ekf . inertial_dead_reckoning ( ) ; // True if this position is estimated through dead-reckoning
2016-08-05 22:26:02 -04:00
2018-07-08 18:11:24 -04:00
_vehicle_global_position_pub . update ( ) ;
2016-08-02 10:30:40 +04:00
}
2015-12-31 18:37:16 +11:00
}
2016-04-01 13:05:38 +02:00
2017-03-08 10:55:33 +11:00
{
2017-09-21 16:24:53 -04:00
// publish all corrected sensor readings and bias estimates after mag calibration is updated above
2019-08-07 05:05:48 -04:00
sensor_bias_s bias { } ;
2017-09-21 16:24:53 -04:00
bias . timestamp = now ;
2018-07-08 18:11:24 -04:00
// In-run bias estimates
2019-08-07 05:05:48 -04:00
_ekf . get_gyro_bias ( bias . gyro_bias ) ;
_ekf . get_accel_bias ( bias . accel_bias ) ;
bias . mag_bias [ 0 ] = _last_valid_mag_cal [ 0 ] ;
bias . mag_bias [ 1 ] = _last_valid_mag_cal [ 1 ] ;
bias . mag_bias [ 2 ] = _last_valid_mag_cal [ 2 ] ;
2018-07-08 18:11:24 -04:00
2019-06-12 08:48:19 -04:00
_sensor_bias_pub . publish ( bias ) ;
2017-09-21 16:24:53 -04:00
}
2018-07-08 18:11:24 -04:00
// publish estimator status
estimator_status_s status ;
status . timestamp = now ;
_ekf . get_state_delayed ( status . states ) ;
2018-06-24 20:54:12 -04:00
status . n_states = 24 ;
2019-03-13 08:26:31 +11:00
_ekf . covariances_diagonal ( ) . copyTo ( status . covariances ) ;
2018-07-08 18:11:24 -04:00
_ekf . get_gps_check_status ( & status . gps_check_fail_flags ) ;
2018-09-27 16:47:52 +02:00
// only report enabled GPS check failures (the param indexes are shifted by 1 bit, because they don't include
// the GPS Fix bit, which is always checked)
status . gps_check_fail_flags & = ( ( uint16_t ) _params - > gps_check_mask < < 1 ) | 1 ;
2018-07-08 18:11:24 -04:00
status . control_mode_flags = control_status . value ;
_ekf . get_filter_fault_status ( & status . filter_fault_flags ) ;
_ekf . get_innovation_test_status ( & status . innovation_check_flags , & status . mag_test_ratio ,
& status . vel_test_ratio , & status . pos_test_ratio ,
& status . hgt_test_ratio , & status . tas_test_ratio ,
& status . hagl_test_ratio , & status . beta_test_ratio ) ;
status . pos_horiz_accuracy = _vehicle_local_position_pub . get ( ) . eph ;
status . pos_vert_accuracy = _vehicle_local_position_pub . get ( ) . epv ;
_ekf . get_ekf_soln_status ( & status . solution_status_flags ) ;
_ekf . get_imu_vibe_metrics ( status . vibe ) ;
status . time_slip = _last_time_slip_us / 1e6 f ;
status . health_flags = 0.0f ; // unused
status . timeout_flags = 0.0f ; // unused
status . pre_flt_fail = _preflt_fail ;
2019-06-12 08:48:19 -04:00
_estimator_status_pub . publish ( status ) ;
2017-03-08 10:55:33 +11:00
2018-07-23 13:26:57 +10:00
// publish GPS drift data only when updated to minimise overhead
float gps_drift [ 3 ] ;
bool blocked ;
if ( _ekf . get_gps_drift_metrics ( gps_drift , & blocked ) ) {
ekf_gps_drift_s drift_data ;
drift_data . timestamp = now ;
drift_data . hpos_drift_rate = gps_drift [ 0 ] ;
drift_data . vpos_drift_rate = gps_drift [ 1 ] ;
drift_data . hspd = gps_drift [ 2 ] ;
drift_data . blocked = blocked ;
2019-06-12 08:48:19 -04:00
_ekf_gps_drift_pub . publish ( drift_data ) ;
2018-07-23 13:26:57 +10:00
}
2017-11-07 15:55:50 -05:00
{
2017-05-17 21:54:41 +10:00
/* Check and save learned magnetometer bias estimates */
2018-10-18 16:26:09 +02:00
// Check if conditions are OK for learning of magnetometer bias values
2017-05-17 21:54:41 +10:00
if ( ! vehicle_land_detected . landed & & // not on ground
( vehicle_status . arming_state = = vehicle_status_s : : ARMING_STATE_ARMED ) & & // vehicle is armed
2018-07-08 18:11:24 -04:00
! status . filter_fault_flags & & // there are no filter faults
control_status . flags . mag_3D ) { // the EKF is operating in the correct mode
2017-11-07 15:55:50 -05:00
2017-05-17 21:54:41 +10:00
if ( _last_magcal_us = = 0 ) {
_last_magcal_us = now ;
} else {
_total_cal_time_us + = now - _last_magcal_us ;
_last_magcal_us = now ;
}
} else if ( status . filter_fault_flags ! = 0 ) {
// if a filter fault has occurred, assume previous learning was invalid and do not
// count it towards total learning time.
_total_cal_time_us = 0 ;
2017-11-07 15:55:50 -05:00
for ( bool & cal_available : _valid_cal_available ) {
cal_available = false ;
}
2017-05-17 21:54:41 +10:00
}
// Start checking mag bias estimates when we have accumulated sufficient calibration time
2018-07-08 18:11:24 -04:00
if ( _total_cal_time_us > 120 _s ) {
2017-05-17 21:54:41 +10:00
// we have sufficient accumulated valid flight time to form a reliable bias estimate
// check that the state variance for each axis is within a range indicating filter convergence
2019-03-26 10:44:53 +01:00
const float max_var_allowed = 100.0f * _param_ekf2_magb_vref . get ( ) ;
const float min_var_allowed = 0.01f * _param_ekf2_magb_vref . get ( ) ;
2017-04-22 09:58:34 +10:00
2017-05-17 21:54:41 +10:00
// Declare all bias estimates invalid if any variances are out of range
bool all_estimates_invalid = false ;
2017-05-18 11:28:12 +10:00
2017-03-30 09:21:47 +11:00
for ( uint8_t axis_index = 0 ; axis_index < = 2 ; axis_index + + ) {
2017-05-17 21:54:41 +10:00
if ( status . covariances [ axis_index + 19 ] < min_var_allowed
| | status . covariances [ axis_index + 19 ] > max_var_allowed ) {
all_estimates_invalid = true ;
}
}
// Store valid estimates and their associated variances
if ( ! all_estimates_invalid ) {
for ( uint8_t axis_index = 0 ; axis_index < = 2 ; axis_index + + ) {
2017-03-30 09:21:47 +11:00
_last_valid_mag_cal [ axis_index ] = status . states [ axis_index + 19 ] ;
_valid_cal_available [ axis_index ] = true ;
_last_valid_variance [ axis_index ] = status . covariances [ axis_index + 19 ] ;
}
}
}
// Check and save the last valid calibration when we are disarmed
2017-05-17 21:54:41 +10:00
if ( ( vehicle_status . arming_state = = vehicle_status_s : : ARMING_STATE_STANDBY )
& & ( status . filter_fault_flags = = 0 )
2019-03-26 10:44:53 +01:00
& & ( sensor_selection . mag_device_id = = ( uint32_t ) _param_ekf2_magbias_id . get ( ) ) ) {
2017-11-07 15:55:50 -05:00
2019-03-26 10:44:53 +01:00
update_mag_bias ( _param_ekf2_magbias_x , 0 ) ;
update_mag_bias ( _param_ekf2_magbias_y , 1 ) ;
update_mag_bias ( _param_ekf2_magbias_z , 2 ) ;
2017-03-30 09:21:47 +11:00
2017-05-17 21:54:41 +10:00
// reset to prevent data being saved too frequently
_total_cal_time_us = 0 ;
2017-03-30 09:21:47 +11:00
}
2018-07-25 08:53:28 +10:00
}
publish_wind_estimate ( now ) ;
if ( ! _mag_decl_saved & & ( vehicle_status . arming_state = = vehicle_status_s : : ARMING_STATE_STANDBY ) ) {
2019-03-26 10:44:53 +01:00
_mag_decl_saved = update_mag_decl ( _param_ekf2_mag_decl ) ;
2017-03-08 10:55:33 +11:00
}
{
2017-09-21 16:24:53 -04:00
// publish estimator innovation data
2017-09-05 12:56:53 -04:00
ekf2_innovations_s innovations ;
2017-03-30 09:21:47 +11:00
innovations . timestamp = now ;
2017-03-08 10:55:33 +11:00
_ekf . get_vel_pos_innov ( & innovations . vel_pos_innov [ 0 ] ) ;
2018-01-14 23:22:38 +05:30
_ekf . get_aux_vel_innov ( & innovations . aux_vel_innov [ 0 ] ) ;
2017-03-08 10:55:33 +11:00
_ekf . get_mag_innov ( & innovations . mag_innov [ 0 ] ) ;
_ekf . get_heading_innov ( & innovations . heading_innov ) ;
_ekf . get_airspeed_innov ( & innovations . airspeed_innov ) ;
_ekf . get_beta_innov ( & innovations . beta_innov ) ;
_ekf . get_flow_innov ( & innovations . flow_innov [ 0 ] ) ;
_ekf . get_hagl_innov ( & innovations . hagl_innov ) ;
2017-08-01 07:29:08 +10:00
_ekf . get_drag_innov ( & innovations . drag_innov [ 0 ] ) ;
2017-03-08 10:55:33 +11:00
_ekf . get_vel_pos_innov_var ( & innovations . vel_pos_innov_var [ 0 ] ) ;
_ekf . get_mag_innov_var ( & innovations . mag_innov_var [ 0 ] ) ;
_ekf . get_heading_innov_var ( & innovations . heading_innov_var ) ;
_ekf . get_airspeed_innov_var ( & innovations . airspeed_innov_var ) ;
_ekf . get_beta_innov_var ( & innovations . beta_innov_var ) ;
_ekf . get_flow_innov_var ( & innovations . flow_innov_var [ 0 ] ) ;
_ekf . get_hagl_innov_var ( & innovations . hagl_innov_var ) ;
2017-08-01 07:29:08 +10:00
_ekf . get_drag_innov_var ( & innovations . drag_innov_var [ 0 ] ) ;
2017-03-08 10:55:33 +11:00
_ekf . get_output_tracking_error ( & innovations . output_tracking_error [ 0 ] ) ;
2017-05-16 20:55:50 +10:00
// calculate noise filtered velocity innovations which are used for pre-flight checking
if ( vehicle_status . arming_state = = vehicle_status_s : : ARMING_STATE_STANDBY ) {
2017-11-24 12:19:11 +11:00
// calculate coefficients for LPF applied to innovation sequences
2017-09-21 16:24:53 -04:00
float alpha = constrain ( sensors . accelerometer_integral_dt / 1.e6 f * _innov_lpf_tau_inv , 0.0f , 1.0f ) ;
2017-05-16 20:55:50 +10:00
float beta = 1.0f - alpha ;
2017-11-24 12:19:11 +11:00
// filter the velocity and innvovations
_vel_ne_innov_lpf ( 0 ) = beta * _vel_ne_innov_lpf ( 0 ) + alpha * constrain ( innovations . vel_pos_innov [ 0 ] ,
- _vel_innov_spike_lim , _vel_innov_spike_lim ) ;
_vel_ne_innov_lpf ( 1 ) = beta * _vel_ne_innov_lpf ( 1 ) + alpha * constrain ( innovations . vel_pos_innov [ 1 ] ,
- _vel_innov_spike_lim , _vel_innov_spike_lim ) ;
_vel_d_innov_lpf = beta * _vel_d_innov_lpf + alpha * constrain ( innovations . vel_pos_innov [ 2 ] ,
- _vel_innov_spike_lim , _vel_innov_spike_lim ) ;
2017-12-07 11:49:24 +11:00
// set the max allowed yaw innovaton depending on whether we are not aiding navigation using
// observations in the NE reference frame.
2018-07-08 18:11:24 -04:00
bool doing_ne_aiding = control_status . flags . gps | | control_status . flags . ev_pos ;
2017-12-07 22:08:30 +11:00
2017-12-08 08:43:47 +11:00
float yaw_test_limit ;
2019-06-11 12:54:22 +02:00
if ( doing_ne_aiding & & vehicle_status . vehicle_type = = vehicle_status_s : : VEHICLE_TYPE_ROTARY_WING ) {
2018-06-12 10:04:15 +10:00
// use a smaller tolerance when doing NE inertial frame aiding as a rotary wing
// vehicle which cannot use GPS course to realign heading in flight
2017-12-07 11:49:24 +11:00
yaw_test_limit = _nav_yaw_innov_test_lim ;
} else {
2018-06-12 10:04:15 +10:00
// use a larger tolerance when not doing NE inertial frame aiding or
// if a fixed wing vehicle which can realign heading using GPS course
2017-12-07 11:49:24 +11:00
yaw_test_limit = _yaw_innov_test_lim ;
}
2018-06-12 10:04:15 +10:00
// filter the yaw innovations
_yaw_innov_magnitude_lpf = beta * _yaw_innov_magnitude_lpf + alpha * constrain ( innovations . heading_innov ,
- 2.0f * yaw_test_limit , 2.0f * yaw_test_limit ) ;
2017-11-24 12:19:11 +11:00
2017-09-21 16:24:53 -04:00
_hgt_innov_lpf = beta * _hgt_innov_lpf + alpha * constrain ( innovations . vel_pos_innov [ 5 ] , - _hgt_innov_spike_lim ,
2017-05-16 20:55:50 +10:00
_hgt_innov_spike_lim ) ;
2017-11-24 12:19:11 +11:00
// check the yaw and horizontal velocity innovations
float vel_ne_innov_length = sqrtf ( innovations . vel_pos_innov [ 0 ] * innovations . vel_pos_innov [ 0 ] +
innovations . vel_pos_innov [ 1 ] * innovations . vel_pos_innov [ 1 ] ) ;
_preflt_horiz_fail = ( _vel_ne_innov_lpf . norm ( ) > _vel_innov_test_lim )
| | ( vel_ne_innov_length > 2.0f * _vel_innov_test_lim )
2017-12-07 11:49:24 +11:00
| | ( _yaw_innov_magnitude_lpf > yaw_test_limit ) ;
2017-11-24 12:19:11 +11:00
// check the vertical velocity and position innovations
_preflt_vert_fail = ( fabsf ( _vel_d_innov_lpf ) > _vel_innov_test_lim )
| | ( fabsf ( innovations . vel_pos_innov [ 2 ] ) > 2.0f * _vel_innov_test_lim )
| | ( fabsf ( _hgt_innov_lpf ) > _hgt_innov_test_lim ) ;
// master pass-fail status
_preflt_fail = _preflt_horiz_fail | | _preflt_vert_fail ;
2017-05-16 20:55:50 +10:00
} else {
2017-11-24 12:19:11 +11:00
_vel_ne_innov_lpf . zero ( ) ;
_vel_d_innov_lpf = 0.0f ;
2017-05-16 20:55:50 +10:00
_hgt_innov_lpf = 0.0f ;
2017-11-24 12:19:11 +11:00
_preflt_horiz_fail = false ;
_preflt_vert_fail = false ;
_preflt_fail = false ;
2017-05-16 20:55:50 +10:00
}
2019-06-12 08:48:19 -04:00
_estimator_innovations_pub . publish ( innovations ) ;
2017-03-08 10:55:33 +11:00
}
2015-12-31 18:37:16 +11:00
}
2016-01-12 07:32:38 +01:00
2018-03-19 14:17:16 -04:00
// publish ekf2_timestamps
2019-06-12 08:48:19 -04:00
_ekf2_timestamps_pub . publish ( ekf2_timestamps ) ;
2015-11-26 23:53:29 +01:00
}
2017-09-22 08:50:26 +02:00
}
2019-05-30 11:46:37 -04:00
int Ekf2 : : getRangeSubIndex ( )
2017-09-22 08:50:26 +02:00
{
for ( unsigned i = 0 ; i < ORB_MULTI_MAX_INSTANCES ; i + + ) {
2019-05-30 11:46:37 -04:00
distance_sensor_s report { } ;
2017-09-22 08:50:26 +02:00
2019-05-30 11:46:37 -04:00
if ( _range_finder_subs [ i ] . update ( & report ) ) {
2017-09-22 08:50:26 +02:00
// only use the first instace which has the correct orientation
if ( report . orientation = = distance_sensor_s : : ROTATION_DOWNWARD_FACING ) {
PX4_INFO ( " Found range finder with instance %d " , i ) ;
return i ;
}
}
}
return - 1 ;
2015-11-26 23:53:29 +01:00
}
2018-08-04 16:19:24 +02:00
bool Ekf2 : : publish_attitude ( const sensor_combined_s & sensors , const hrt_abstime & now )
2018-03-14 13:46:19 -04:00
{
2018-07-08 18:11:24 -04:00
if ( _ekf . attitude_valid ( ) ) {
// generate vehicle attitude quaternion data
vehicle_attitude_s att ;
2018-08-04 16:19:24 +02:00
att . timestamp = now ;
2018-07-08 18:11:24 -04:00
const Quatf q { _ekf . calculate_quaternion ( ) } ;
q . copyTo ( att . q ) ;
_ekf . get_quat_reset ( & att . delta_q_reset [ 0 ] , & att . quat_reset_counter ) ;
2019-06-12 08:48:19 -04:00
_att_pub . publish ( att ) ;
2018-07-08 18:11:24 -04:00
return true ;
} else if ( _replay_mode ) {
// in replay mode we have to tell the replay module not to wait for an update
// we do this by publishing an attitude with zero timestamp
2019-06-12 08:48:19 -04:00
vehicle_attitude_s att { } ;
_att_pub . publish ( att ) ;
2018-07-08 18:11:24 -04:00
}
return false ;
}
bool Ekf2 : : publish_wind_estimate ( const hrt_abstime & timestamp )
{
2018-03-14 13:46:19 -04:00
if ( _ekf . get_wind_status ( ) ) {
2019-08-29 15:48:46 +02:00
// Publish wind estimate only if ekf declares them valid
wind_estimate_s wind_estimate { } ;
2018-03-14 13:46:19 -04:00
float velNE_wind [ 2 ] ;
float wind_var [ 2 ] ;
2019-08-29 15:48:46 +02:00
_ekf . get_wind_velocity ( velNE_wind ) ;
2018-03-14 13:46:19 -04:00
_ekf . get_wind_velocity_var ( wind_var ) ;
2019-08-29 15:48:46 +02:00
_ekf . get_airspeed_innov ( & wind_estimate . tas_innov ) ;
_ekf . get_airspeed_innov_var ( & wind_estimate . tas_innov_var ) ;
_ekf . get_beta_innov ( & wind_estimate . beta_innov ) ;
_ekf . get_beta_innov_var ( & wind_estimate . beta_innov_var ) ;
2018-03-14 13:46:19 -04:00
wind_estimate . timestamp = timestamp ;
wind_estimate . windspeed_north = velNE_wind [ 0 ] ;
wind_estimate . windspeed_east = velNE_wind [ 1 ] ;
wind_estimate . variance_north = wind_var [ 0 ] ;
wind_estimate . variance_east = wind_var [ 1 ] ;
2019-08-29 15:48:46 +02:00
wind_estimate . tas_scale = 0.0f ; //leave at 0 as scale is not estimated in ekf
2018-03-14 13:46:19 -04:00
2019-06-12 08:48:19 -04:00
_wind_pub . publish ( wind_estimate ) ;
2018-03-14 13:46:19 -04:00
2018-07-08 18:11:24 -04:00
return true ;
2018-03-14 13:46:19 -04:00
}
2018-07-08 18:11:24 -04:00
return false ;
2018-03-14 13:46:19 -04:00
}
const Vector3f Ekf2 : : get_vel_body_wind ( )
{
// Used to correct baro data for positional errors
2019-09-16 11:12:23 +02:00
matrix : : Quatf q = _ekf . get_quaternion ( ) ;
2018-03-14 13:46:19 -04:00
matrix : : Dcmf R_to_body ( q . inversed ( ) ) ;
// Calculate wind-compensated velocity in body frame
// Velocity of body origin in local NED frame (m/s)
float velocity [ 3 ] ;
_ekf . get_velocity ( velocity ) ;
float velNE_wind [ 2 ] ;
_ekf . get_wind_velocity ( velNE_wind ) ;
Vector3f v_wind_comp = { velocity [ 0 ] - velNE_wind [ 0 ] , velocity [ 1 ] - velNE_wind [ 1 ] , velocity [ 2 ] } ;
return R_to_body * v_wind_comp ;
}
2018-09-29 23:23:19 +10:00
bool Ekf2 : : blend_gps_data ( )
2018-07-23 02:18:30 +10:00
{
// zero the blend weights
memset ( & _blend_weights , 0 , sizeof ( _blend_weights ) ) ;
2018-09-29 23:23:19 +10:00
/*
* If both receivers have the same update rate , use the oldest non - zero time .
* If two receivers with different update rates are used , use the slowest .
* If time difference is excessive , use newest to prevent a disconnected receiver
* from blocking updates .
*/
// Calculate the time step for each receiver with some filtering to reduce the effects of jitter
// Find the largest and smallest time step.
float dt_max = 0.0f ;
float dt_min = 0.3f ;
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
float raw_dt = 0.001f * ( float ) ( _gps_state [ i ] . time_usec - _time_prev_us [ i ] ) ;
if ( raw_dt > 0.0f & & raw_dt < 0.3f ) {
_gps_dt [ i ] = 0.1f * raw_dt + 0.9f * _gps_dt [ i ] ;
}
if ( _gps_dt [ i ] > dt_max ) {
dt_max = _gps_dt [ i ] ;
_gps_slowest_index = i ;
}
if ( _gps_dt [ i ] < dt_min ) {
dt_min = _gps_dt [ i ] ;
}
}
// Find the receiver that is last be updated
2018-07-23 02:18:30 +10:00
uint64_t max_us = 0 ; // newest non-zero system time of arrival of a GPS message
uint64_t min_us = - 1 ; // oldest non-zero system time of arrival of a GPS message
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
// Find largest and smallest times
if ( _gps_state [ i ] . time_usec > max_us ) {
max_us = _gps_state [ i ] . time_usec ;
2018-09-29 23:23:19 +10:00
_gps_newest_index = i ;
2018-07-23 02:18:30 +10:00
}
if ( ( _gps_state [ i ] . time_usec < min_us ) & & ( _gps_state [ i ] . time_usec > 0 ) ) {
min_us = _gps_state [ i ] . time_usec ;
2018-09-29 23:23:19 +10:00
_gps_oldest_index = i ;
2018-07-23 02:18:30 +10:00
}
}
2018-09-29 23:23:19 +10:00
if ( ( max_us - min_us ) > 300000 ) {
// A receiver has timed out so fall out of blending
2018-07-23 02:18:30 +10:00
return false ;
}
2018-09-29 23:23:19 +10:00
/*
* If the largest dt is less than 20 % greater than the smallest , then we have receivers
* running at the same rate then we wait until we have two messages with an arrival time
* difference that is less than 50 % of the smallest time step and use the time stamp from
* the newest data .
* Else we have two receivers at different update rates and use the slowest receiver
* as the timing reference .
*/
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
if ( ( dt_max - dt_min ) < 0.2f * dt_min ) {
// both receivers assumed to be running at the same rate
if ( ( max_us - min_us ) < ( uint64_t ) ( 5e5 f * dt_min ) ) {
// data arrival within a short time window enables the two measurements to be blended
_gps_time_ref_index = _gps_newest_index ;
_gps_new_output_data = true ;
2018-07-23 02:18:30 +10:00
}
2018-09-29 23:23:19 +10:00
} else {
// both receivers running at different rates
_gps_time_ref_index = _gps_slowest_index ;
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
if ( _gps_state [ _gps_time_ref_index ] . time_usec > _time_prev_us [ _gps_time_ref_index ] ) {
// blend data at the rate of the slower receiver
_gps_new_output_data = true ;
2018-07-23 02:18:30 +10:00
}
}
2018-09-29 23:23:19 +10:00
if ( _gps_new_output_data ) {
_gps_blended_state . time_usec = _gps_state [ _gps_time_ref_index ] . time_usec ;
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
// calculate the sum squared speed accuracy across all GPS sensors
float speed_accuracy_sum_sq = 0.0f ;
2018-07-23 02:18:30 +10:00
2019-03-26 10:44:53 +01:00
if ( _param_ekf2_gps_mask . get ( ) & BLEND_MASK_USE_SPD_ACC ) {
2018-09-29 23:23:19 +10:00
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
if ( _gps_state [ i ] . fix_type > = 3 & & _gps_state [ i ] . sacc > 0.0f ) {
speed_accuracy_sum_sq + = _gps_state [ i ] . sacc * _gps_state [ i ] . sacc ;
} else {
// not all receivers support this metric so set it to zero and don't use it
speed_accuracy_sum_sq = 0.0f ;
break ;
}
2018-07-23 02:18:30 +10:00
}
}
2018-09-29 23:23:19 +10:00
// calculate the sum squared horizontal position accuracy across all GPS sensors
float horizontal_accuracy_sum_sq = 0.0f ;
2018-07-23 02:18:30 +10:00
2019-03-26 10:44:53 +01:00
if ( _param_ekf2_gps_mask . get ( ) & BLEND_MASK_USE_HPOS_ACC ) {
2018-09-29 23:23:19 +10:00
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
if ( _gps_state [ i ] . fix_type > = 2 & & _gps_state [ i ] . eph > 0.0f ) {
horizontal_accuracy_sum_sq + = _gps_state [ i ] . eph * _gps_state [ i ] . eph ;
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
} else {
// not all receivers support this metric so set it to zero and don't use it
horizontal_accuracy_sum_sq = 0.0f ;
break ;
}
}
}
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
// calculate the sum squared vertical position accuracy across all GPS sensors
float vertical_accuracy_sum_sq = 0.0f ;
2018-07-23 02:18:30 +10:00
2019-03-26 10:44:53 +01:00
if ( _param_ekf2_gps_mask . get ( ) & BLEND_MASK_USE_VPOS_ACC ) {
2018-09-29 23:23:19 +10:00
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
if ( _gps_state [ i ] . fix_type > = 3 & & _gps_state [ i ] . epv > 0.0f ) {
vertical_accuracy_sum_sq + = _gps_state [ i ] . epv * _gps_state [ i ] . epv ;
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
} else {
// not all receivers support this metric so set it to zero and don't use it
vertical_accuracy_sum_sq = 0.0f ;
break ;
}
2018-07-23 02:18:30 +10:00
}
}
2018-09-29 23:23:19 +10:00
// Check if we can do blending using reported accuracy
bool can_do_blending = ( horizontal_accuracy_sum_sq > 0.0f | | vertical_accuracy_sum_sq > 0.0f
| | speed_accuracy_sum_sq > 0.0f ) ;
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
// if we can't do blending using reported accuracy, return false and hard switch logic will be used instead
if ( ! can_do_blending ) {
return false ;
2018-07-23 02:18:30 +10:00
}
2018-09-29 23:23:19 +10:00
float sum_of_all_weights = 0.0f ;
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
// calculate a weighting using the reported speed accuracy
float spd_blend_weights [ GPS_MAX_RECEIVERS ] = { } ;
2018-07-23 02:18:30 +10:00
2019-03-26 10:44:53 +01:00
if ( speed_accuracy_sum_sq > 0.0f & & ( _param_ekf2_gps_mask . get ( ) & BLEND_MASK_USE_SPD_ACC ) ) {
2018-09-29 23:23:19 +10:00
// calculate the weights using the inverse of the variances
float sum_of_spd_weights = 0.0f ;
2018-07-23 02:18:30 +10:00
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
2018-09-29 23:23:19 +10:00
if ( _gps_state [ i ] . fix_type > = 3 & & _gps_state [ i ] . sacc > = 0.001f ) {
spd_blend_weights [ i ] = 1.0f / ( _gps_state [ i ] . sacc * _gps_state [ i ] . sacc ) ;
sum_of_spd_weights + = spd_blend_weights [ i ] ;
}
2018-07-23 02:18:30 +10:00
}
2018-09-29 23:23:19 +10:00
// normalise the weights
if ( sum_of_spd_weights > 0.0f ) {
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
spd_blend_weights [ i ] = spd_blend_weights [ i ] / sum_of_spd_weights ;
}
sum_of_all_weights + = 1.0f ;
}
2018-07-23 02:18:30 +10:00
}
2018-09-29 23:23:19 +10:00
// calculate a weighting using the reported horizontal position
float hpos_blend_weights [ GPS_MAX_RECEIVERS ] = { } ;
2018-07-23 02:18:30 +10:00
2019-03-26 10:44:53 +01:00
if ( horizontal_accuracy_sum_sq > 0.0f & & ( _param_ekf2_gps_mask . get ( ) & BLEND_MASK_USE_HPOS_ACC ) ) {
2018-09-29 23:23:19 +10:00
// calculate the weights using the inverse of the variances
float sum_of_hpos_weights = 0.0f ;
2018-07-23 02:18:30 +10:00
2018-09-29 23:23:19 +10:00
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
if ( _gps_state [ i ] . fix_type > = 2 & & _gps_state [ i ] . eph > = 0.001f ) {
hpos_blend_weights [ i ] = horizontal_accuracy_sum_sq / ( _gps_state [ i ] . eph * _gps_state [ i ] . eph ) ;
sum_of_hpos_weights + = hpos_blend_weights [ i ] ;
}
}
// normalise the weights
if ( sum_of_hpos_weights > 0.0f ) {
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
hpos_blend_weights [ i ] = hpos_blend_weights [ i ] / sum_of_hpos_weights ;
}
sum_of_all_weights + = 1.0f ;
2018-07-23 02:18:30 +10:00
}
}
2018-09-29 23:23:19 +10:00
// calculate a weighting using the reported vertical position accuracy
float vpos_blend_weights [ GPS_MAX_RECEIVERS ] = { } ;
2019-03-26 10:44:53 +01:00
if ( vertical_accuracy_sum_sq > 0.0f & & ( _param_ekf2_gps_mask . get ( ) & BLEND_MASK_USE_VPOS_ACC ) ) {
2018-09-29 23:23:19 +10:00
// calculate the weights using the inverse of the variances
float sum_of_vpos_weights = 0.0f ;
2018-07-23 02:18:30 +10:00
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
2018-09-29 23:23:19 +10:00
if ( _gps_state [ i ] . fix_type > = 3 & & _gps_state [ i ] . epv > = 0.001f ) {
vpos_blend_weights [ i ] = vertical_accuracy_sum_sq / ( _gps_state [ i ] . epv * _gps_state [ i ] . epv ) ;
sum_of_vpos_weights + = vpos_blend_weights [ i ] ;
}
2018-07-23 02:18:30 +10:00
}
2018-09-29 23:23:19 +10:00
// normalise the weights
if ( sum_of_vpos_weights > 0.0f ) {
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
vpos_blend_weights [ i ] = vpos_blend_weights [ i ] / sum_of_vpos_weights ;
}
sum_of_all_weights + = 1.0f ;
} ;
}
// calculate an overall weight
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
_blend_weights [ i ] = ( hpos_blend_weights [ i ] + vpos_blend_weights [ i ] + spd_blend_weights [ i ] ) / sum_of_all_weights ;
}
// With updated weights we can calculate a blended GPS solution and
// offsets for each physical receiver
update_gps_blend_states ( ) ;
update_gps_offsets ( ) ;
_gps_select_index = 2 ;
2018-07-23 02:18:30 +10:00
}
return true ;
}
/*
* Update the internal state estimate for a blended GPS solution that is a weighted average of the phsyical receiver solutions
* with weights are calculated in calc_gps_blend_weights ( ) . This internal state cannot be used directly by estimators
* because if physical receivers have significant position differences , variation in receiver estimated accuracy will
2018-10-18 16:32:11 +02:00
* cause undesirable variation in the position solution .
2018-07-23 02:18:30 +10:00
*/
void Ekf2 : : update_gps_blend_states ( )
{
// initialise the blended states so we can accumulate the results using the weightings for each GPS receiver.
_gps_blended_state . time_usec = 0 ;
_gps_blended_state . lat = 0 ;
_gps_blended_state . lon = 0 ;
_gps_blended_state . alt = 0 ;
_gps_blended_state . fix_type = 0 ;
_gps_blended_state . eph = FLT_MAX ;
_gps_blended_state . epv = FLT_MAX ;
_gps_blended_state . sacc = FLT_MAX ;
_gps_blended_state . vel_m_s = 0.0f ;
_gps_blended_state . vel_ned [ 0 ] = 0.0f ;
_gps_blended_state . vel_ned [ 1 ] = 0.0f ;
_gps_blended_state . vel_ned [ 2 ] = 0.0f ;
_gps_blended_state . vel_ned_valid = true ;
_gps_blended_state . nsats = 0 ;
_gps_blended_state . gdop = FLT_MAX ;
_blended_antenna_offset . zero ( ) ;
// combine the the GPS states into a blended solution using the weights calculated in calc_blend_weights()
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
// blend the timing data
_gps_blended_state . time_usec + = ( uint64_t ) ( ( double ) _gps_state [ i ] . time_usec * ( double ) _blend_weights [ i ] ) ;
// use the highest status
if ( _gps_state [ i ] . fix_type > _gps_blended_state . fix_type ) {
_gps_blended_state . fix_type = _gps_state [ i ] . fix_type ;
}
// calculate a blended average speed and velocity vector
_gps_blended_state . vel_m_s + = _gps_state [ i ] . vel_m_s * _blend_weights [ i ] ;
_gps_blended_state . vel_ned [ 0 ] + = _gps_state [ i ] . vel_ned [ 0 ] * _blend_weights [ i ] ;
_gps_blended_state . vel_ned [ 1 ] + = _gps_state [ i ] . vel_ned [ 1 ] * _blend_weights [ i ] ;
_gps_blended_state . vel_ned [ 2 ] + = _gps_state [ i ] . vel_ned [ 2 ] * _blend_weights [ i ] ;
// Assume blended error magnitude, DOP and sat count is equal to the best value from contributing receivers
// If any receiver contributing has an invalid velocity, then report blended velocity as invalid
if ( _blend_weights [ i ] > 0.0f ) {
if ( _gps_state [ i ] . eph > 0.0f
& & _gps_state [ i ] . eph < _gps_blended_state . eph ) {
_gps_blended_state . eph = _gps_state [ i ] . eph ;
}
if ( _gps_state [ i ] . epv > 0.0f
& & _gps_state [ i ] . epv < _gps_blended_state . epv ) {
_gps_blended_state . epv = _gps_state [ i ] . epv ;
}
if ( _gps_state [ i ] . sacc > 0.0f
& & _gps_state [ i ] . sacc < _gps_blended_state . sacc ) {
_gps_blended_state . sacc = _gps_state [ i ] . sacc ;
}
if ( _gps_state [ i ] . gdop > 0
& & _gps_state [ i ] . gdop < _gps_blended_state . gdop ) {
_gps_blended_state . gdop = _gps_state [ i ] . gdop ;
}
if ( _gps_state [ i ] . nsats > 0
& & _gps_state [ i ] . nsats > _gps_blended_state . nsats ) {
_gps_blended_state . nsats = _gps_state [ i ] . nsats ;
}
if ( ! _gps_state [ i ] . vel_ned_valid ) {
_gps_blended_state . vel_ned_valid = false ;
}
}
// TODO read parameters for individual GPS antenna positions and blend
// Vector3f temp_antenna_offset = _antenna_offset[i];
// temp_antenna_offset *= _blend_weights[i];
// _blended_antenna_offset += temp_antenna_offset;
}
/*
* Calculate the instantaneous weighted average location using available GPS instances and store in _gps_state .
* This is statistically the most likely location , but may not be stable enough for direct use by the EKF .
*/
// Use the GPS with the highest weighting as the reference position
float best_weight = 0.0f ;
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
if ( _blend_weights [ i ] > best_weight ) {
best_weight = _blend_weights [ i ] ;
_gps_best_index = i ;
_gps_blended_state . lat = _gps_state [ i ] . lat ;
_gps_blended_state . lon = _gps_state [ i ] . lon ;
_gps_blended_state . alt = _gps_state [ i ] . alt ;
}
}
// Convert each GPS position to a local NEU offset relative to the reference position
Vector2f blended_NE_offset_m ;
blended_NE_offset_m . zero ( ) ;
float blended_alt_offset_mm = 0.0f ;
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
if ( ( _blend_weights [ i ] > 0.0f ) & & ( i ! = _gps_best_index ) ) {
// calculate the horizontal offset
Vector2f horiz_offset { } ;
get_vector_to_next_waypoint ( ( _gps_blended_state . lat / 1.0e7 ) ,
( _gps_blended_state . lon / 1.0e7 ) , ( _gps_state [ i ] . lat / 1.0e7 ) , ( _gps_state [ i ] . lon / 1.0e7 ) ,
& horiz_offset ( 0 ) , & horiz_offset ( 1 ) ) ;
// sum weighted offsets
blended_NE_offset_m + = horiz_offset * _blend_weights [ i ] ;
// calculate vertical offset
float vert_offset = ( float ) ( _gps_state [ i ] . alt - _gps_blended_state . alt ) ;
// sum weighted offsets
blended_alt_offset_mm + = vert_offset * _blend_weights [ i ] ;
}
}
// Add the sum of weighted offsets to the reference position to obtain the blended position
double lat_deg_now = ( double ) _gps_blended_state . lat * 1.0e-7 ;
double lon_deg_now = ( double ) _gps_blended_state . lon * 1.0e-7 ;
double lat_deg_res , lon_deg_res ;
add_vector_to_global_position ( lat_deg_now , lon_deg_now , blended_NE_offset_m ( 0 ) , blended_NE_offset_m ( 1 ) , & lat_deg_res ,
& lon_deg_res ) ;
_gps_blended_state . lat = ( int32_t ) ( 1.0E7 * lat_deg_res ) ;
_gps_blended_state . lon = ( int32_t ) ( 1.0E7 * lon_deg_res ) ;
_gps_blended_state . alt + = ( int32_t ) blended_alt_offset_mm ;
2018-08-16 14:40:41 +10:00
// Take GPS heading from the highest weighted receiver that is publishing a valid .heading value
uint8_t gps_best_yaw_index = 0 ;
best_weight = 0.0f ;
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
if ( PX4_ISFINITE ( _gps_state [ i ] . yaw ) & & ( _blend_weights [ i ] > best_weight ) ) {
best_weight = _blend_weights [ i ] ;
gps_best_yaw_index = i ;
}
}
_gps_blended_state . yaw = _gps_state [ gps_best_yaw_index ] . yaw ;
_gps_blended_state . yaw_offset = _gps_state [ gps_best_yaw_index ] . yaw_offset ;
2018-07-23 02:18:30 +10:00
}
/*
* The location in _gps_blended_state will move around as the relative accuracy changes .
* To mitigate this effect a low - pass filtered offset from each GPS location to the blended location is
* calculated .
*/
void Ekf2 : : update_gps_offsets ( )
{
// Calculate filter coefficients to be applied to the offsets for each GPS position and height offset
// Increase the filter time constant proportional to the inverse of the weighting
// A weighting of 1 will make the offset adjust the slowest, a weighting of 0 will make it adjust with zero filtering
float alpha [ GPS_MAX_RECEIVERS ] = { } ;
2019-03-26 10:44:53 +01:00
float omega_lpf = 1.0f / fmaxf ( _param_ekf2_gps_tau . get ( ) , 1.0f ) ;
2018-07-23 02:18:30 +10:00
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
if ( _gps_state [ i ] . time_usec - _time_prev_us [ i ] > 0 ) {
// calculate the filter coefficient that achieves the time constant specified by the user adjustable parameter
float min_alpha = constrain ( omega_lpf * 1e-6 f * ( float ) ( _gps_state [ i ] . time_usec - _time_prev_us [ i ] ) ,
0.0f , 1.0f ) ;
// scale the filter coefficient so that time constant is inversely proprtional to weighting
if ( _blend_weights [ i ] > min_alpha ) {
alpha [ i ] = min_alpha / _blend_weights [ i ] ;
} else {
alpha [ i ] = 1.0f ;
}
_time_prev_us [ i ] = _gps_state [ i ] . time_usec ;
}
}
// Calculate a filtered position delta for each GPS relative to the blended solution state
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
Vector2f offset ;
get_vector_to_next_waypoint ( ( _gps_state [ i ] . lat / 1.0e7 ) , ( _gps_state [ i ] . lon / 1.0e7 ) ,
( _gps_blended_state . lat / 1.0e7 ) , ( _gps_blended_state . lon / 1.0e7 ) , & offset ( 0 ) , & offset ( 1 ) ) ;
_NE_pos_offset_m [ i ] = offset * alpha [ i ] + _NE_pos_offset_m [ i ] * ( 1.0f - alpha [ i ] ) ;
_hgt_offset_mm [ i ] = ( float ) ( _gps_blended_state . alt - _gps_state [ i ] . alt ) * alpha [ i ] +
_hgt_offset_mm [ i ] * ( 1.0f - alpha [ i ] ) ;
}
// calculate offset limits from the largest difference between receivers
Vector2f max_ne_offset { } ;
float max_alt_offset = 0 ;
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
for ( uint8_t j = i ; j < GPS_MAX_RECEIVERS ; j + + ) {
if ( i ! = j ) {
Vector2f offset ;
get_vector_to_next_waypoint ( ( _gps_state [ i ] . lat / 1.0e7 ) , ( _gps_state [ i ] . lon / 1.0e7 ) ,
( _gps_state [ j ] . lat / 1.0e7 ) , ( _gps_state [ j ] . lon / 1.0e7 ) , & offset ( 0 ) , & offset ( 1 ) ) ;
max_ne_offset ( 0 ) = fmaxf ( max_ne_offset ( 0 ) , fabsf ( offset ( 0 ) ) ) ;
max_ne_offset ( 1 ) = fmaxf ( max_ne_offset ( 1 ) , fabsf ( offset ( 1 ) ) ) ;
max_alt_offset = fmaxf ( max_alt_offset , fabsf ( ( float ) ( _gps_state [ i ] . alt - _gps_state [ j ] . alt ) ) ) ;
}
}
}
// apply offset limits
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
_NE_pos_offset_m [ i ] ( 0 ) = constrain ( _NE_pos_offset_m [ i ] ( 0 ) , - max_ne_offset ( 0 ) , max_ne_offset ( 0 ) ) ;
_NE_pos_offset_m [ i ] ( 1 ) = constrain ( _NE_pos_offset_m [ i ] ( 1 ) , - max_ne_offset ( 1 ) , max_ne_offset ( 1 ) ) ;
_hgt_offset_mm [ i ] = constrain ( _hgt_offset_mm [ i ] , - max_alt_offset , max_alt_offset ) ;
}
}
/*
* Apply the steady state physical receiver offsets calculated by update_gps_offsets ( ) .
*/
void Ekf2 : : apply_gps_offsets ( )
{
// calculate offset corrected output for each physical GPS.
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
// Add the sum of weighted offsets to the reference position to obtain the blended position
double lat_deg_now = ( double ) _gps_state [ i ] . lat * 1.0e-7 ;
double lon_deg_now = ( double ) _gps_state [ i ] . lon * 1.0e-7 ;
double lat_deg_res , lon_deg_res ;
add_vector_to_global_position ( lat_deg_now , lon_deg_now , _NE_pos_offset_m [ i ] ( 0 ) , _NE_pos_offset_m [ i ] ( 1 ) , & lat_deg_res ,
& lon_deg_res ) ;
_gps_output [ i ] . lat = ( int32_t ) ( 1.0E7 * lat_deg_res ) ;
_gps_output [ i ] . lon = ( int32_t ) ( 1.0E7 * lon_deg_res ) ;
_gps_output [ i ] . alt = _gps_state [ i ] . alt + ( int32_t ) _hgt_offset_mm [ i ] ;
// other receiver data is used uncorrected
_gps_output [ i ] . time_usec = _gps_state [ i ] . time_usec ;
_gps_output [ i ] . fix_type = _gps_state [ i ] . fix_type ;
_gps_output [ i ] . vel_m_s = _gps_state [ i ] . vel_m_s ;
_gps_output [ i ] . vel_ned [ 0 ] = _gps_state [ i ] . vel_ned [ 0 ] ;
_gps_output [ i ] . vel_ned [ 1 ] = _gps_state [ i ] . vel_ned [ 1 ] ;
_gps_output [ i ] . vel_ned [ 2 ] = _gps_state [ i ] . vel_ned [ 2 ] ;
_gps_output [ i ] . eph = _gps_state [ i ] . eph ;
_gps_output [ i ] . epv = _gps_state [ i ] . epv ;
_gps_output [ i ] . sacc = _gps_state [ i ] . sacc ;
_gps_output [ i ] . gdop = _gps_state [ i ] . gdop ;
_gps_output [ i ] . nsats = _gps_state [ i ] . nsats ;
_gps_output [ i ] . vel_ned_valid = _gps_state [ i ] . vel_ned_valid ;
2018-08-16 14:40:41 +10:00
_gps_output [ i ] . yaw = _gps_state [ i ] . yaw ;
_gps_output [ i ] . yaw_offset = _gps_state [ i ] . yaw_offset ;
2018-07-23 02:18:30 +10:00
}
}
/*
Calculate GPS output that is a blend of the offset corrected physical receiver data
*/
void Ekf2 : : calc_gps_blend_output ( )
{
// Convert each GPS position to a local NEU offset relative to the reference position
// which is defined as the positon of the blended solution calculated from non offset corrected data
Vector2f blended_NE_offset_m ;
blended_NE_offset_m . zero ( ) ;
float blended_alt_offset_mm = 0.0f ;
for ( uint8_t i = 0 ; i < GPS_MAX_RECEIVERS ; i + + ) {
if ( _blend_weights [ i ] > 0.0f ) {
// calculate the horizontal offset
Vector2f horiz_offset { } ;
get_vector_to_next_waypoint ( ( _gps_blended_state . lat / 1.0e7 ) ,
( _gps_blended_state . lon / 1.0e7 ) ,
( _gps_output [ i ] . lat / 1.0e7 ) ,
( _gps_output [ i ] . lon / 1.0e7 ) ,
& horiz_offset ( 0 ) ,
& horiz_offset ( 1 ) ) ;
// sum weighted offsets
blended_NE_offset_m + = horiz_offset * _blend_weights [ i ] ;
// calculate vertical offset
float vert_offset = ( float ) ( _gps_output [ i ] . alt - _gps_blended_state . alt ) ;
// sum weighted offsets
blended_alt_offset_mm + = vert_offset * _blend_weights [ i ] ;
}
}
// Add the sum of weighted offsets to the reference position to obtain the blended position
double lat_deg_now = ( double ) _gps_blended_state . lat * 1.0e-7 ;
double lon_deg_now = ( double ) _gps_blended_state . lon * 1.0e-7 ;
double lat_deg_res , lon_deg_res ;
add_vector_to_global_position ( lat_deg_now , lon_deg_now , blended_NE_offset_m ( 0 ) , blended_NE_offset_m ( 1 ) , & lat_deg_res ,
& lon_deg_res ) ;
_gps_output [ GPS_BLENDED_INSTANCE ] . lat = ( int32_t ) ( 1.0E7 * lat_deg_res ) ;
_gps_output [ GPS_BLENDED_INSTANCE ] . lon = ( int32_t ) ( 1.0E7 * lon_deg_res ) ;
_gps_output [ GPS_BLENDED_INSTANCE ] . alt = _gps_blended_state . alt + ( int32_t ) blended_alt_offset_mm ;
// Copy remaining data from internal states to output
_gps_output [ GPS_BLENDED_INSTANCE ] . time_usec = _gps_blended_state . time_usec ;
_gps_output [ GPS_BLENDED_INSTANCE ] . fix_type = _gps_blended_state . fix_type ;
_gps_output [ GPS_BLENDED_INSTANCE ] . vel_m_s = _gps_blended_state . vel_m_s ;
_gps_output [ GPS_BLENDED_INSTANCE ] . vel_ned [ 0 ] = _gps_blended_state . vel_ned [ 0 ] ;
_gps_output [ GPS_BLENDED_INSTANCE ] . vel_ned [ 1 ] = _gps_blended_state . vel_ned [ 1 ] ;
_gps_output [ GPS_BLENDED_INSTANCE ] . vel_ned [ 2 ] = _gps_blended_state . vel_ned [ 2 ] ;
_gps_output [ GPS_BLENDED_INSTANCE ] . eph = _gps_blended_state . eph ;
_gps_output [ GPS_BLENDED_INSTANCE ] . epv = _gps_blended_state . epv ;
_gps_output [ GPS_BLENDED_INSTANCE ] . sacc = _gps_blended_state . sacc ;
_gps_output [ GPS_BLENDED_INSTANCE ] . gdop = _gps_blended_state . gdop ;
_gps_output [ GPS_BLENDED_INSTANCE ] . nsats = _gps_blended_state . nsats ;
_gps_output [ GPS_BLENDED_INSTANCE ] . vel_ned_valid = _gps_blended_state . vel_ned_valid ;
2018-08-16 14:40:41 +10:00
_gps_output [ GPS_BLENDED_INSTANCE ] . yaw = _gps_blended_state . yaw ;
_gps_output [ GPS_BLENDED_INSTANCE ] . yaw_offset = _gps_blended_state . yaw_offset ;
2018-07-23 02:18:30 +10:00
}
2018-09-07 10:42:29 +02:00
float Ekf2 : : filter_altitude_ellipsoid ( float amsl_hgt )
{
float height_diff = static_cast < float > ( _gps_alttitude_ellipsoid [ 0 ] ) * 1e-3 f - amsl_hgt ;
if ( _gps_alttitude_ellipsoid_previous_timestamp [ 0 ] = = 0 ) {
_wgs84_hgt_offset = height_diff ;
_gps_alttitude_ellipsoid_previous_timestamp [ 0 ] = _gps_state [ 0 ] . time_usec ;
} else if ( _gps_state [ 0 ] . time_usec ! = _gps_alttitude_ellipsoid_previous_timestamp [ 0 ] ) {
// apply a 10 second first order low pass filter to baro offset
float dt = 1e-6 f * static_cast < float > ( _gps_state [ 0 ] . time_usec - _gps_alttitude_ellipsoid_previous_timestamp [ 0 ] ) ;
_gps_alttitude_ellipsoid_previous_timestamp [ 0 ] = _gps_state [ 0 ] . time_usec ;
float offset_rate_correction = 0.1f * ( height_diff - _wgs84_hgt_offset ) ;
_wgs84_hgt_offset + = dt * math : : constrain ( offset_rate_correction , - 0.1f , 0.1f ) ;
}
return amsl_hgt + _wgs84_hgt_offset ;
}
2018-07-23 02:18:30 +10:00
2017-05-10 10:32:45 +02:00
Ekf2 * Ekf2 : : instantiate ( int argc , char * argv [ ] )
2015-11-26 23:53:29 +01:00
{
2017-05-10 10:32:45 +02:00
Ekf2 * instance = new Ekf2 ( ) ;
2015-11-26 23:53:29 +01:00
2017-05-10 10:32:45 +02:00
if ( instance ) {
if ( argc > = 2 & & ! strcmp ( argv [ 1 ] , " -r " ) ) {
instance - > set_replay_mode ( true ) ;
}
2015-11-26 23:53:29 +01:00
}
2017-05-10 10:32:45 +02:00
return instance ;
2015-11-26 23:53:29 +01:00
}
2017-05-10 10:32:45 +02:00
int Ekf2 : : custom_command ( int argc , char * argv [ ] )
2015-11-26 23:53:29 +01:00
{
2017-05-10 10:32:45 +02:00
return print_usage ( " unknown command " ) ;
}
2015-11-26 23:53:29 +01:00
2017-05-10 10:32:45 +02:00
int Ekf2 : : print_usage ( const char * reason )
{
if ( reason ) {
PX4_WARN ( " %s \n " , reason ) ;
2015-11-26 23:53:29 +01:00
}
2017-05-10 10:32:45 +02:00
PRINT_MODULE_DESCRIPTION (
R " DESCR_STR(
# ## Description
Attitude and position estimator using an Extended Kalman Filter . It is used for Multirotors and Fixed - Wing .
2015-11-26 23:53:29 +01:00
2019-02-19 10:05:57 +11:00
The documentation can be found on the [ ECL / EKF Overview & Tuning ] ( https : //docs.px4.io/en/advanced_config/tuning_the_ecl_ekf.html) page.
2016-01-22 12:07:17 +01:00
2017-05-10 10:32:45 +02:00
ekf2 can be started in replay mode ( ` - r ` ) : in this mode it does not access the system time , but only uses the
timestamps from the sensor topics .
2016-01-22 12:07:17 +01:00
2017-05-10 10:32:45 +02:00
) DESCR_STR " );
2015-11-26 23:53:29 +01:00
2017-05-10 10:32:45 +02:00
PRINT_MODULE_USAGE_NAME ( " ekf2 " , " estimator " ) ;
PRINT_MODULE_USAGE_COMMAND ( " start " ) ;
PRINT_MODULE_USAGE_PARAM_FLAG ( ' r ' , " Enable replay mode " , true ) ;
PRINT_MODULE_USAGE_DEFAULT_COMMANDS ( ) ;
2016-01-09 10:51:09 +01:00
2017-05-10 10:32:45 +02:00
return 0 ;
}
2015-11-26 23:53:29 +01:00
2017-05-10 10:32:45 +02:00
int Ekf2 : : task_spawn ( int argc , char * argv [ ] )
{
_task_id = px4_task_spawn_cmd ( " ekf2 " ,
SCHED_DEFAULT ,
2017-07-09 21:38:37 +02:00
SCHED_PRIORITY_ESTIMATOR ,
2017-11-13 08:39:35 +11:00
6600 ,
2017-05-10 10:32:45 +02:00
( px4_main_t ) & run_trampoline ,
( char * const * ) argv ) ;
if ( _task_id < 0 ) {
_task_id = - 1 ;
return - errno ;
2015-11-26 23:53:29 +01:00
}
2017-05-10 10:32:45 +02:00
return 0 ;
}
2015-11-26 23:53:29 +01:00
2017-05-10 10:32:45 +02:00
int ekf2_main ( int argc , char * argv [ ] )
{
return Ekf2 : : main ( argc , argv ) ;
2016-01-25 13:14:50 +11:00
}