#pragma once #include #include #include #include #include #include #include #include // uORB Subscriptions #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include // uORB Publications #include #include #include #include #include #include using namespace matrix; using namespace control; using namespace time_literals; static const float DELAY_MAX = 0.5f; // seconds static const float HIST_STEP = 0.05f; // 20 hz static const float BIAS_MAX = 1e-1f; static const size_t HIST_LEN = 10; // DELAY_MAX / HIST_STEP; static const size_t N_DIST_SUBS = 4; // for fault detection // chi squared distribution, false alarm probability 0.0001 // see fault_table.py // note skip 0 index so we can use degree of freedom as index static const float BETA_TABLE[7] = {0, 8.82050518214, 12.094592431, 13.9876612368, 16.0875642296, 17.8797700658, 19.6465647819, }; class BlockLocalPositionEstimator : public ModuleBase, public ModuleParams, public px4::WorkItem, public control::SuperBlock { // dynamics: // // x(+) = A * x(-) + B * u(+) // y_i = C_i*x // // kalman filter // // E[xx'] = P // E[uu'] = W // E[y_iy_i'] = R_i // // prediction // x(+|-) = A*x(-|-) + B*u(+) // P(+|-) = A*P(-|-)*A' + B*W*B' // // correction // x(+|+) = x(+|-) + K_i * (y_i - H_i * x(+|-) ) // // // input: // ax, ay, az (acceleration NED) // // states: // px, py, pz , ( position NED, m) // vx, vy, vz ( vel NED, m/s), // bx, by, bz ( accel bias, m/s^2) // tz (terrain altitude, ASL, m) // // measurements: // // sonar: pz (measured d*cos(phi)*cos(theta)) // // baro: pz // // flow: vx, vy (flow is in body x, y frame) // // gps: px, py, pz, vx, vy, vz (flow is in body x, y frame) // // lidar: pz (actual measured d*cos(phi)*cos(theta)) // // vision: px, py, pz, vx, vy, vz // // mocap: px, py, pz // // land (detects when landed)): pz (always measures agl = 0) // public: BlockLocalPositionEstimator(); ~BlockLocalPositionEstimator() override; /** @see ModuleBase */ static int task_spawn(int argc, char *argv[]); /** @see ModuleBase */ static int custom_command(int argc, char *argv[]); /** @see ModuleBase */ static int print_usage(const char *reason = nullptr); bool init(); private: // constants enum {X_x = 0, X_y, X_z, X_vx, X_vy, X_vz, X_bx, X_by, X_bz, X_tz, n_x}; enum {U_ax = 0, U_ay, U_az, n_u}; enum {Y_baro_z = 0, n_y_baro}; enum {Y_lidar_z = 0, n_y_lidar}; enum {Y_flow_vx = 0, Y_flow_vy, n_y_flow}; enum {Y_sonar_z = 0, n_y_sonar}; enum {Y_gps_x = 0, Y_gps_y, Y_gps_z, Y_gps_vx, Y_gps_vy, Y_gps_vz, n_y_gps}; enum {Y_vision_x = 0, Y_vision_y, Y_vision_z, n_y_vision}; enum {Y_mocap_x = 0, Y_mocap_y, Y_mocap_z, n_y_mocap}; enum {Y_land_vx = 0, Y_land_vy, Y_land_agl, n_y_land}; enum {Y_target_x = 0, Y_target_y, n_y_target}; enum { FUSE_GPS = 1 << 0, FUSE_FLOW = 1 << 1, FUSE_VIS_POS = 1 << 2, FUSE_LAND_TARGET = 1 << 3, FUSE_LAND = 1 << 4, FUSE_PUB_AGL_Z = 1 << 5, FUSE_FLOW_GYRO_COMP = 1 << 6, FUSE_BARO = 1 << 7 }; enum sensor_t { SENSOR_BARO = 1 << 0, SENSOR_GPS = 1 << 1, SENSOR_LIDAR = 1 << 2, SENSOR_FLOW = 1 << 3, SENSOR_SONAR = 1 << 4, SENSOR_VISION = 1 << 5, SENSOR_MOCAP = 1 << 6, SENSOR_LAND = 1 << 7, SENSOR_LAND_TARGET = 1 << 8, }; enum estimate_t { EST_XY = 1 << 0, EST_Z = 1 << 1, EST_TZ = 1 << 2, }; void Run() override; // methods // ---------------------------- // Vector dynamics( float t, const Vector &x, const Vector &u); void initP(); void initSS(); void updateSSStates(); void updateSSParams(); // predict the next state void predict(const sensor_combined_s &imu); // lidar int lidarMeasure(Vector &y); void lidarCorrect(); void lidarInit(); void lidarCheckTimeout(); // sonar int sonarMeasure(Vector &y); void sonarCorrect(); void sonarInit(); void sonarCheckTimeout(); // baro int baroMeasure(Vector &y); void baroCorrect(); void baroInit(); void baroCheckTimeout(); // gps int gpsMeasure(Vector &y); void gpsCorrect(); void gpsInit(); void gpsCheckTimeout(); // flow int flowMeasure(Vector &y); void flowCorrect(); void flowInit(); void flowCheckTimeout(); // vision int visionMeasure(Vector &y); void visionCorrect(); void visionInit(); void visionCheckTimeout(); // mocap int mocapMeasure(Vector &y); void mocapCorrect(); void mocapInit(); void mocapCheckTimeout(); // land int landMeasure(Vector &y); void landCorrect(); void landInit(); void landCheckTimeout(); // landing target int landingTargetMeasure(Vector &y); void landingTargetCorrect(); void landingTargetInit(); void landingTargetCheckTimeout(); // timeouts void checkTimeouts(); // misc inline float agl() { return _x(X_tz) - _x(X_z); } bool landed(); int getDelayPeriods(float delay, uint8_t *periods); // publications void publishLocalPos(); void publishGlobalPos(); void publishOdom(); void publishEstimatorStatus(); void publishEk2fTimestamps(); // attributes // ---------------------------- // subscriptions uORB::SubscriptionCallbackWorkItem _sensors_sub{this, ORB_ID(sensor_combined)}; uORB::SubscriptionData _sub_armed{ORB_ID(actuator_armed)}; uORB::SubscriptionData _sub_land{ORB_ID(vehicle_land_detected)}; uORB::SubscriptionData _sub_att{ORB_ID(vehicle_attitude)}; uORB::SubscriptionData _sub_angular_velocity{ORB_ID(vehicle_angular_velocity)}; uORB::SubscriptionData _sub_flow{ORB_ID(optical_flow)}; uORB::SubscriptionData _sub_param_update{ORB_ID(parameter_update)}; uORB::SubscriptionData _sub_gps{ORB_ID(vehicle_gps_position)}; uORB::SubscriptionData _sub_visual_odom{ORB_ID(vehicle_visual_odometry)}; uORB::SubscriptionData _sub_mocap_odom{ORB_ID(vehicle_mocap_odometry)}; uORB::SubscriptionData _sub_dist0{ORB_ID(distance_sensor), 0}; uORB::SubscriptionData _sub_dist1{ORB_ID(distance_sensor), 1}; uORB::SubscriptionData _sub_dist2{ORB_ID(distance_sensor), 2}; uORB::SubscriptionData _sub_dist3{ORB_ID(distance_sensor), 3}; uORB::SubscriptionData *_dist_subs[N_DIST_SUBS] {}; uORB::SubscriptionData *_sub_lidar{nullptr}; uORB::SubscriptionData *_sub_sonar{nullptr}; uORB::SubscriptionData _sub_landing_target_pose{ORB_ID(landing_target_pose)}; uORB::SubscriptionData _sub_airdata{ORB_ID(vehicle_air_data)}; // publications uORB::PublicationData _pub_lpos{ORB_ID(vehicle_local_position)}; uORB::PublicationData _pub_gpos{ORB_ID(vehicle_global_position)}; uORB::PublicationData _pub_odom{ORB_ID(vehicle_odometry)}; uORB::PublicationData _pub_est_states{ORB_ID(estimator_states)}; uORB::PublicationData _pub_est_status{ORB_ID(estimator_status)}; uORB::PublicationData _pub_innov{ORB_ID(estimator_innovations)}; uORB::PublicationData _pub_innov_var{ORB_ID(estimator_innovation_variances)}; // map projection struct map_projection_reference_s _map_ref; // target mode paramters from landing_target_estimator module enum TargetMode { Target_Moving = 0, Target_Stationary = 1 }; // flow gyro filter BlockHighPass _flow_gyro_x_high_pass; BlockHighPass _flow_gyro_y_high_pass; // stats BlockStats _baroStats; BlockStats _sonarStats; BlockStats _lidarStats; BlockStats _flowQStats; BlockStats _visionStats; BlockStats _mocapStats; BlockStats _gpsStats; uint16_t _landCount; // low pass BlockLowPassVector _xLowPass; BlockLowPass _aglLowPass; // delay blocks BlockDelay _xDelay; BlockDelay _tDelay; // misc uint64_t _timeStamp; uint64_t _time_origin; uint64_t _timeStampLastBaro; uint64_t _time_last_hist; uint64_t _time_last_flow; uint64_t _time_last_baro; uint64_t _time_last_gps; uint64_t _time_last_lidar; uint64_t _time_last_sonar; uint64_t _time_init_sonar; uint64_t _time_last_vision_p; uint64_t _time_last_mocap; uint64_t _time_last_land; uint64_t _time_last_target; int _lockstep_component{-1}; // reference altitudes float _altOrigin; bool _altOriginInitialized; bool _altOriginGlobal; // true when the altitude of the origin is defined wrt a global reference frame float _baroAltOrigin; float _gpsAltOrigin; // status bool _receivedGps; bool _lastArmedState; // masks uint16_t _sensorTimeout; uint16_t _sensorFault; uint8_t _estimatorInitialized; // sensor update flags bool _flowUpdated; bool _gpsUpdated; bool _visionUpdated; bool _mocapUpdated; bool _lidarUpdated; bool _sonarUpdated; bool _landUpdated; bool _baroUpdated; // sensor validation flags bool _vision_xy_valid; bool _vision_z_valid; bool _mocap_xy_valid; bool _mocap_z_valid; // sensor std deviations float _vision_eph; float _vision_epv; float _mocap_eph; float _mocap_epv; // local to global coversion related variables bool _is_global_cov_init; uint64_t _global_ref_timestamp; double _ref_lat; double _ref_lon; float _ref_alt; // state space Vector _x; // state vector Vector _u; // input vector Matrix m_P; // state covariance matrix matrix::Dcm _R_att; Matrix m_A; // dynamics matrix Matrix m_B; // input matrix Matrix m_R; // input covariance Matrix m_Q; // process noise covariance DEFINE_PARAMETERS( (ParamInt) _param_sys_autostart, /**< example parameter */ // general parameters (ParamInt) _param_lpe_fusion, (ParamFloat) _param_lpe_vxy_pub, (ParamFloat) _param_lpe_z_pub, // sonar parameters (ParamFloat) _param_lpe_snr_z, (ParamFloat) _param_lpe_snr_off_z, // lidar parameters (ParamFloat) _param_lpe_ldr_z, (ParamFloat) _param_lpe_ldr_off_z, // accel parameters (ParamFloat) _param_lpe_acc_xy, (ParamFloat) _param_lpe_acc_z, // baro parameters (ParamFloat) _param_lpe_bar_z, // gps parameters (ParamFloat) _param_lpe_gps_delay, (ParamFloat) _param_lpe_gps_xy, (ParamFloat) _param_lpe_gps_z, (ParamFloat) _param_lpe_gps_vxy, (ParamFloat) _param_lpe_gps_vz, (ParamFloat) _param_lpe_eph_max, (ParamFloat) _param_lpe_epv_max, // vision parameters (ParamFloat) _param_lpe_vis_xy, (ParamFloat) _param_lpe_vis_z, (ParamFloat) _param_lpe_vis_delay, // mocap parameters (ParamFloat) _param_lpe_vic_p, // flow parameters (ParamFloat) _param_lpe_flw_off_z, (ParamFloat) _param_lpe_flw_scale, (ParamInt) _param_lpe_flw_qmin, (ParamFloat) _param_lpe_flw_r, (ParamFloat) _param_lpe_flw_rr, // land parameters (ParamFloat) _param_lpe_land_z, (ParamFloat) _param_lpe_land_vxy, // process noise (ParamFloat) _param_lpe_pn_p, (ParamFloat) _param_lpe_pn_v, (ParamFloat) _param_lpe_pn_b, (ParamFloat) _param_lpe_pn_t, (ParamFloat) _param_lpe_t_max_grade, (ParamFloat) _param_lpe_lt_cov, (ParamInt) _param_ltest_mode, // init origin (ParamInt) _param_lpe_fake_origin, (ParamFloat) _param_lpe_lat, (ParamFloat) _param_lpe_lon ) };