123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615 |
- #pragma once
- #define AP_INERTIAL_SENSOR_ACCEL_TOT_MAX_OFFSET_CHANGE 4.0f
- #define AP_INERTIAL_SENSOR_ACCEL_MAX_OFFSET 250.0f
- #define AP_INERTIAL_SENSOR_ACCEL_VIBE_FLOOR_FILT_HZ 5.0f
- #define AP_INERTIAL_SENSOR_ACCEL_VIBE_FILT_HZ 2.0f
- #define AP_INERTIAL_SENSOR_ACCEL_PEAK_DETECT_TIMEOUT_MS 500
- #define INS_MAX_INSTANCES 3
- #define INS_MAX_BACKENDS 6
- #define INS_VIBRATION_CHECK_INSTANCES 2
- #define DEFAULT_IMU_LOG_BAT_MASK 0
- #include <stdint.h>
- #include <AP_AccelCal/AP_AccelCal.h>
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Math/AP_Math.h>
- #include <Filter/LowPassFilter2p.h>
- #include <Filter/LowPassFilter.h>
- #include <Filter/NotchFilter.h>
- #include <Filter/HarmonicNotchFilter.h>
- class AP_InertialSensor_Backend;
- class AuxiliaryBus;
- class AP_AHRS;
- class AP_Logger;
- class AP_InertialSensor : AP_AccelCal_Client
- {
- friend class AP_InertialSensor_Backend;
- public:
- AP_InertialSensor();
-
- AP_InertialSensor(const AP_InertialSensor &other) = delete;
- AP_InertialSensor &operator=(const AP_InertialSensor&) = delete;
- static AP_InertialSensor *get_singleton();
- enum Gyro_Calibration_Timing {
- GYRO_CAL_NEVER = 0,
- GYRO_CAL_STARTUP_ONLY = 1
- };
-
-
-
-
-
-
-
-
- void init(uint16_t sample_rate_hz);
-
-
- uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id);
- uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id);
-
- void periodic();
- bool calibrate_trim(float &trim_roll, float &trim_pitch);
-
- bool calibrating() const { return _calibrating; }
-
-
-
-
-
- void init_gyro(void);
-
-
-
-
- const Vector3f &get_gyro(uint8_t i) const { return _gyro[i]; }
- const Vector3f &get_gyro(void) const { return get_gyro(_primary_gyro); }
-
- const Vector3f &get_gyro_offsets(uint8_t i) const { return _gyro_offset[i]; }
- const Vector3f &get_gyro_offsets(void) const { return get_gyro_offsets(_primary_gyro); }
-
- bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const;
- bool get_delta_angle(Vector3f &delta_angle) const { return get_delta_angle(_primary_gyro, delta_angle); }
- float get_delta_angle_dt(uint8_t i) const;
- float get_delta_angle_dt() const { return get_delta_angle_dt(_primary_accel); }
-
- bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const;
- bool get_delta_velocity(Vector3f &delta_velocity) const { return get_delta_velocity(_primary_accel, delta_velocity); }
- float get_delta_velocity_dt(uint8_t i) const;
- float get_delta_velocity_dt() const { return get_delta_velocity_dt(_primary_accel); }
-
-
-
-
- const Vector3f &get_accel(uint8_t i) const { return _accel[i]; }
- const Vector3f &get_accel(void) const { return get_accel(_primary_accel); }
- uint32_t get_gyro_error_count(uint8_t i) const { return _gyro_error_count[i]; }
- uint32_t get_accel_error_count(uint8_t i) const { return _accel_error_count[i]; }
-
- bool get_gyro_health(uint8_t instance) const { return (instance<_gyro_count) ? _gyro_healthy[instance] : false; }
- bool get_gyro_health(void) const { return get_gyro_health(_primary_gyro); }
- bool get_gyro_health_all(void) const;
- uint8_t get_gyro_count(void) const { return _gyro_count; }
- bool gyro_calibrated_ok(uint8_t instance) const { return _gyro_cal_ok[instance]; }
- bool gyro_calibrated_ok_all() const;
- bool use_gyro(uint8_t instance) const;
- Gyro_Calibration_Timing gyro_calibration_timing();
- bool get_accel_health(uint8_t instance) const { return (instance<_accel_count) ? _accel_healthy[instance] : false; }
- bool get_accel_health(void) const { return get_accel_health(_primary_accel); }
- bool get_accel_health_all(void) const;
- uint8_t get_accel_count(void) const { return _accel_count; }
- bool accel_calibrated_ok_all() const;
- bool use_accel(uint8_t instance) const;
-
- uint16_t get_gyro_rate_hz(uint8_t instance) const { return uint16_t(_gyro_raw_sample_rates[instance] * _gyro_over_sampling[instance]); }
- uint16_t get_accel_rate_hz(uint8_t instance) const { return uint16_t(_accel_raw_sample_rates[instance] * _accel_over_sampling[instance]); }
-
- const Vector3f &get_accel_offsets(uint8_t i) const { return _accel_offset[i]; }
- const Vector3f &get_accel_offsets(void) const { return get_accel_offsets(_primary_accel); }
-
- const Vector3f &get_accel_scale(uint8_t i) const { return _accel_scale[i]; }
- const Vector3f &get_accel_scale(void) const { return get_accel_scale(_primary_accel); }
-
- const Vector3f &get_imu_pos_offset(uint8_t instance) const {
- return _accel_pos[instance];
- }
- const Vector3f &get_imu_pos_offset(void) const {
- return _accel_pos[_primary_accel];
- }
-
-
- float get_temperature(uint8_t instance) const { return _temperature[instance]; }
-
- float get_delta_time() const { return MIN(_delta_time, _loop_delta_t_max); }
-
-
- float get_gyro_drift_rate(void) const { return ToRad(0.5f/60); }
-
- void update(void);
-
- void wait_for_sample(void);
-
- static const struct AP_Param::GroupInfo var_info[];
-
- void set_board_orientation(enum Rotation orientation, Matrix3f* custom_rotation = nullptr) {
- _board_orientation = orientation;
- _custom_rotation = custom_rotation;
- }
-
- uint16_t get_sample_rate(void) const { return _sample_rate; }
-
- float get_loop_delta_t(void) const { return _loop_delta_t; }
- bool healthy(void) const { return get_gyro_health() && get_accel_health(); }
- uint8_t get_primary_accel(void) const { return _primary_accel; }
- uint8_t get_primary_gyro(void) const { return _primary_gyro; }
-
- void update_harmonic_notch_freq_hz(float scaled_freq);
-
- void set_hil_mode(void) { _hil_mode = true; }
-
- uint16_t get_gyro_filter_hz(void) const { return _gyro_filter_cutoff; }
-
- uint16_t get_accel_filter_hz(void) const { return _accel_filter_cutoff; }
-
- float get_gyro_dynamic_notch_center_freq_hz(void) const { return _calculated_harmonic_notch_freq_hz; }
-
- float get_gyro_harmonic_notch_center_freq_hz(void) const { return _harmonic_notch_filter.center_freq_hz(); }
-
- float get_gyro_harmonic_notch_reference(void) const { return _harmonic_notch_filter.reference(); }
-
- void set_log_raw_bit(uint32_t log_raw_bit) { _log_raw_bit = log_raw_bit; }
-
- void calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt);
-
- Vector3f get_vibration_levels() const { return get_vibration_levels(_primary_accel); }
- Vector3f get_vibration_levels(uint8_t instance) const;
-
- uint32_t get_accel_clip_count(uint8_t instance) const;
-
- bool is_still();
-
- void set_accel(uint8_t instance, const Vector3f &accel);
- void set_gyro(uint8_t instance, const Vector3f &gyro);
- void set_delta_time(float delta_time);
- void set_delta_velocity(uint8_t instance, float deltavt, const Vector3f &deltav);
- void set_delta_angle(uint8_t instance, const Vector3f &deltaa, float deltaat);
- AuxiliaryBus *get_auxiliary_bus(int16_t backend_id) { return get_auxiliary_bus(backend_id, 0); }
- AuxiliaryBus *get_auxiliary_bus(int16_t backend_id, uint8_t instance);
- void detect_backends(void);
-
- void set_accel_peak_hold(uint8_t instance, const Vector3f &accel);
- float get_accel_peak_hold_neg_x() const { return _peak_hold_state.accel_peak_hold_neg_x; }
-
- AP_AccelCal* get_acal() const { return _acal; }
-
- bool get_fixed_mount_accel_cal_sample(uint8_t sample_num, Vector3f& ret) const;
-
- bool get_primary_accel_cal_sample_avg(uint8_t sample_num, Vector3f& ret) const;
-
- bool get_new_trim(float& trim_roll, float &trim_pitch);
-
-
- void acal_init();
-
- void acal_update();
-
- MAV_RESULT simple_accel_cal();
- bool accel_cal_requires_reboot() const { return _accel_cal_requires_reboot; }
-
- uint32_t get_last_update_usec(void) const { return _last_update_usec; }
-
- void kill_imu(uint8_t imu_idx, bool kill_it);
- enum IMU_SENSOR_TYPE {
- IMU_SENSOR_TYPE_ACCEL = 0,
- IMU_SENSOR_TYPE_GYRO = 1,
- };
- class BatchSampler {
- public:
- BatchSampler(const AP_InertialSensor &imu) :
- type(IMU_SENSOR_TYPE_ACCEL),
- _imu(imu) {
- AP_Param::setup_object_defaults(this, var_info);
- };
- void init();
- void sample(uint8_t instance, IMU_SENSOR_TYPE _type, uint64_t sample_us, const Vector3f &sample);
-
- void periodic();
- bool doing_sensor_rate_logging() const { return _doing_sensor_rate_logging; }
- bool doing_post_filter_logging() const { return _doing_post_filter_logging; }
-
- static const struct AP_Param::GroupInfo var_info[];
-
- AP_Int16 _required_count;
- AP_Int8 _sensor_mask;
- AP_Int8 _batch_options_mask;
-
-
-
-
-
-
-
-
- AP_Int16 samples_per_msg;
- AP_Int8 push_interval_ms;
-
- private:
- enum batch_opt_t {
- BATCH_OPT_SENSOR_RATE = (1<<0),
- BATCH_OPT_POST_FILTER = (1<<1),
- };
- void rotate_to_next_sensor();
- void update_doing_sensor_rate_logging();
- bool should_log(uint8_t instance, IMU_SENSOR_TYPE type);
- void push_data_to_log();
- uint64_t measurement_started_us;
- bool initialised : 1;
- bool isbh_sent : 1;
- bool _doing_sensor_rate_logging : 1;
- bool _doing_post_filter_logging : 1;
- uint8_t instance : 3;
- AP_InertialSensor::IMU_SENSOR_TYPE type : 1;
- uint16_t isb_seqnum;
- int16_t *data_x;
- int16_t *data_y;
- int16_t *data_z;
- uint16_t data_write_offset;
- uint16_t data_read_offset;
- uint32_t last_sent_ms;
-
- uint16_t multiplier;
- const AP_InertialSensor &_imu;
- };
- BatchSampler batchsampler{*this};
- private:
-
- bool _add_backend(AP_InertialSensor_Backend *backend);
- void _start_backends();
- AP_InertialSensor_Backend *_find_backend(int16_t backend_id, uint8_t instance);
-
- void _init_gyro();
-
-
-
- bool _calculate_trim(const Vector3f &accel_sample, float& trim_roll, float& trim_pitch);
-
- void _save_gyro_calibration();
-
- AP_InertialSensor_Backend *_backends[INS_MAX_BACKENDS];
-
-
-
- uint8_t _gyro_count;
- uint8_t _accel_count;
- uint8_t _backend_count;
-
- uint16_t _sample_rate;
- float _loop_delta_t;
- float _loop_delta_t_max;
-
- Vector3f _accel[INS_MAX_INSTANCES];
- Vector3f _delta_velocity[INS_MAX_INSTANCES];
- float _delta_velocity_dt[INS_MAX_INSTANCES];
- bool _delta_velocity_valid[INS_MAX_INSTANCES];
-
- Vector3f _delta_velocity_acc[INS_MAX_INSTANCES];
-
- float _delta_velocity_acc_dt[INS_MAX_INSTANCES];
-
- LowPassFilter2pVector3f _accel_filter[INS_MAX_INSTANCES];
- LowPassFilter2pVector3f _gyro_filter[INS_MAX_INSTANCES];
- Vector3f _accel_filtered[INS_MAX_INSTANCES];
- Vector3f _gyro_filtered[INS_MAX_INSTANCES];
- bool _new_accel_data[INS_MAX_INSTANCES];
- bool _new_gyro_data[INS_MAX_INSTANCES];
-
- NotchFilterParams _notch_filter;
- NotchFilterVector3f _gyro_notch_filter[INS_MAX_INSTANCES];
-
- HarmonicNotchFilterParams _harmonic_notch_filter;
- HarmonicNotchFilterVector3f _gyro_harmonic_notch_filter[INS_MAX_INSTANCES];
-
- float _calculated_harmonic_notch_freq_hz;
-
- Vector3f _gyro[INS_MAX_INSTANCES];
- Vector3f _delta_angle[INS_MAX_INSTANCES];
- float _delta_angle_dt[INS_MAX_INSTANCES];
- bool _delta_angle_valid[INS_MAX_INSTANCES];
-
- float _delta_angle_acc_dt[INS_MAX_INSTANCES];
- Vector3f _delta_angle_acc[INS_MAX_INSTANCES];
- Vector3f _last_delta_angle[INS_MAX_INSTANCES];
- Vector3f _last_raw_gyro[INS_MAX_INSTANCES];
-
- uint8_t _accel_sensor_rate_sampling_enabled;
- uint8_t _gyro_sensor_rate_sampling_enabled;
-
- uint16_t _accel_raw_sampling_multiplier[INS_MAX_INSTANCES];
- uint16_t _gyro_raw_sampling_multiplier[INS_MAX_INSTANCES];
-
-
- AP_Int32 _accel_id[INS_MAX_INSTANCES];
- AP_Int32 _gyro_id[INS_MAX_INSTANCES];
-
- AP_Vector3f _accel_scale[INS_MAX_INSTANCES];
- AP_Vector3f _accel_offset[INS_MAX_INSTANCES];
- AP_Vector3f _gyro_offset[INS_MAX_INSTANCES];
-
- AP_Vector3f _accel_pos[INS_MAX_INSTANCES];
-
- float _accel_max_abs_offsets[INS_MAX_INSTANCES];
-
- float _accel_raw_sample_rates[INS_MAX_INSTANCES];
- float _gyro_raw_sample_rates[INS_MAX_INSTANCES];
-
- uint8_t _accel_over_sampling[INS_MAX_INSTANCES];
- uint8_t _gyro_over_sampling[INS_MAX_INSTANCES];
-
-
- uint64_t _accel_last_sample_us[INS_MAX_INSTANCES];
- uint64_t _gyro_last_sample_us[INS_MAX_INSTANCES];
-
- uint16_t _sample_accel_count[INS_MAX_INSTANCES];
- uint32_t _sample_accel_start_us[INS_MAX_INSTANCES];
- uint16_t _sample_gyro_count[INS_MAX_INSTANCES];
- uint32_t _sample_gyro_start_us[INS_MAX_INSTANCES];
-
-
- float _temperature[INS_MAX_INSTANCES];
-
- AP_Int16 _accel_filter_cutoff;
- AP_Int16 _gyro_filter_cutoff;
- AP_Int8 _gyro_cal_timing;
-
- AP_Int8 _use[INS_MAX_INSTANCES];
-
- AP_Int8 _fast_sampling_mask;
-
- AP_Int8 _enable_mask;
-
-
- enum Rotation _board_orientation;
- Matrix3f* _custom_rotation;
-
- enum Rotation _gyro_orientation[INS_MAX_INSTANCES];
- enum Rotation _accel_orientation[INS_MAX_INSTANCES];
-
- bool _gyro_cal_ok[INS_MAX_INSTANCES];
- bool _accel_id_ok[INS_MAX_INSTANCES];
-
- uint8_t _primary_gyro;
- uint8_t _primary_accel;
-
-
- uint8_t _gyro_wait_mask;
- uint8_t _accel_wait_mask;
-
- uint32_t _log_raw_bit;
-
- bool _have_sample:1;
-
- bool _hil_mode:1;
-
- bool _calibrating:1;
- bool _backends_detected:1;
-
- float _delta_time;
-
- uint32_t _last_sample_usec;
-
- uint32_t _next_sample_usec;
-
- uint32_t _sample_period_usec;
-
- uint32_t _last_update_usec;
-
- bool _gyro_healthy[INS_MAX_INSTANCES];
- bool _accel_healthy[INS_MAX_INSTANCES];
- uint32_t _accel_error_count[INS_MAX_INSTANCES];
- uint32_t _gyro_error_count[INS_MAX_INSTANCES];
-
- uint32_t _accel_clip_count[INS_MAX_INSTANCES];
- LowPassFilterVector3f _accel_vibe_floor_filter[INS_VIBRATION_CHECK_INSTANCES];
- LowPassFilterVector3f _accel_vibe_filter[INS_VIBRATION_CHECK_INSTANCES];
-
- struct PeakHoldState {
- float accel_peak_hold_neg_x;
- uint32_t accel_peak_hold_neg_x_age;
- } _peak_hold_state;
-
- AP_Float _still_threshold;
-
- struct {
- float delta_time;
- } _hil {};
-
- AP_Int8 _acc_body_aligned;
- AP_Int8 _trim_option;
- static AP_InertialSensor *_singleton;
- AP_AccelCal* _acal;
- AccelCalibrator *_accel_calibrator;
-
- void _acal_save_calibrations() override;
- void _acal_event_failure() override;
-
- AccelCalibrator* _acal_get_calibrator(uint8_t i) override { return i<get_accel_count()?&(_accel_calibrator[i]):nullptr; }
- float _trim_pitch;
- float _trim_roll;
- bool _new_trim;
- bool _accel_cal_requires_reboot;
-
- uint32_t _accel_startup_error_count[INS_MAX_INSTANCES];
- uint32_t _gyro_startup_error_count[INS_MAX_INSTANCES];
- bool _startup_error_counts_set;
- uint32_t _startup_ms;
- uint8_t imu_kill_mask;
- };
- namespace AP {
- AP_InertialSensor &ins();
- };
|