APM:Libraries
Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes | Friends | List of all members
AP_InertialSensor Class Reference

#include <AP_InertialSensor.h>

Inheritance diagram for AP_InertialSensor:
[legend]
Collaboration diagram for AP_InertialSensor:
[legend]

Classes

class  BatchSampler
 
struct  PeakHoldState
 

Public Types

enum  Gyro_Calibration_Timing { GYRO_CAL_NEVER = 0, GYRO_CAL_STARTUP_ONLY = 1 }
 
enum  IMU_SENSOR_TYPE { IMU_SENSOR_TYPE_ACCEL = 0, IMU_SENSOR_TYPE_GYRO = 1 }
 

Public Member Functions

 AP_InertialSensor ()
 
 AP_InertialSensor (const AP_InertialSensor &other)=delete
 
AP_InertialSensoroperator= (const AP_InertialSensor &)=delete
 
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
 calibrating - returns true if the gyros or accels are currently being calibrated More...
 
void init_gyro (void)
 
const Vector3fget_gyro (uint8_t i) const
 
const Vector3fget_gyro (void) const
 
const Vector3fget_gyro_offsets (uint8_t i) const
 
const Vector3fget_gyro_offsets (void) const
 
bool get_delta_angle (uint8_t i, Vector3f &delta_angle) const
 
bool get_delta_angle (Vector3f &delta_angle) const
 
float get_delta_angle_dt (uint8_t i) const
 
float get_delta_angle_dt () const
 
bool get_delta_velocity (uint8_t i, Vector3f &delta_velocity) const
 
bool get_delta_velocity (Vector3f &delta_velocity) const
 
float get_delta_velocity_dt (uint8_t i) const
 
float get_delta_velocity_dt () const
 
const Vector3fget_accel (uint8_t i) const
 
const Vector3fget_accel (void) const
 
uint32_t get_gyro_error_count (uint8_t i) const
 
uint32_t get_accel_error_count (uint8_t i) const
 
bool get_gyro_health (uint8_t instance) const
 
bool get_gyro_health (void) const
 
bool get_gyro_health_all (void) const
 
uint8_t get_gyro_count (void) const
 
bool gyro_calibrated_ok (uint8_t instance) const
 
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
 
bool get_accel_health (void) const
 
bool get_accel_health_all (void) const
 
uint8_t get_accel_count (void) const
 
bool accel_calibrated_ok_all () const
 
bool use_accel (uint8_t instance) const
 
uint16_t get_gyro_rate_hz (uint8_t instance) const
 
uint16_t get_accel_rate_hz (uint8_t instance) const
 
const Vector3fget_accel_offsets (uint8_t i) const
 
const Vector3fget_accel_offsets (void) const
 
const Vector3fget_accel_scale (uint8_t i) const
 
const Vector3fget_accel_scale (void) const
 
const Vector3fget_imu_pos_offset (uint8_t instance) const
 
const Vector3fget_imu_pos_offset (void) const
 
float get_temperature (uint8_t instance) const
 
float get_delta_time () const
 
float get_gyro_drift_rate (void) const
 
void update (void)
 
void wait_for_sample (void)
 
void set_board_orientation (enum Rotation orientation, Matrix3f *custom_rotation=nullptr)
 
uint16_t get_sample_rate (void) const
 
float get_loop_delta_t (void) const
 
bool healthy (void) const
 
uint8_t get_primary_accel (void) const
 
uint8_t get_primary_gyro (void) const
 
void set_hil_mode (void)
 
uint8_t get_gyro_filter_hz (void) const
 
uint8_t get_accel_filter_hz (void) const
 
void set_log_raw_bit (uint32_t log_raw_bit)
 
void calc_vibration_and_clipping (uint8_t instance, const Vector3f &accel, float dt)
 
Vector3f get_vibration_levels () const
 
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)
 
AuxiliaryBusget_auxiliary_bus (int16_t backend_id)
 
AuxiliaryBusget_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
 
AP_AccelCalget_acal () const
 
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
 
uint32_t get_last_update_usec (void) const
 

Static Public Member Functions

static AP_InertialSensorget_instance ()
 

Public Attributes

BatchSampler batchsampler {*this}
 
float delta_time
 

Static Public Attributes

static const struct AP_Param::GroupInfo var_info []
 

Private Member Functions

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 ()
 
void _acal_save_calibrations ()
 
void _acal_event_failure ()
 
AccelCalibrator_acal_get_calibrator (uint8_t i)
 

Private Attributes

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]
 
NotchFilterVector3fParam _notch_filter
 
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_Int16 _old_product_id
 
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_Int8 _accel_filter_cutoff
 
AP_Int8 _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
 
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 AP_InertialSensor::PeakHoldState _peak_hold_state
 
AP_Float _still_threshold
 
struct {
   float   delta_time
 
_hil
 
AP_Int8 _acc_body_aligned
 
AP_Int8 _trim_option
 
AP_AccelCal_acal
 
AccelCalibrator_accel_calibrator
 
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
 

Static Private Attributes

static AP_InertialSensor_s_instance = nullptr
 

Friends

class AP_InertialSensor_Backend
 

Detailed Description

Definition at line 47 of file AP_InertialSensor.h.

Member Enumeration Documentation

◆ Gyro_Calibration_Timing

Enumerator
GYRO_CAL_NEVER 
GYRO_CAL_STARTUP_ONLY 

Definition at line 60 of file AP_InertialSensor.h.

◆ IMU_SENSOR_TYPE

Enumerator
IMU_SENSOR_TYPE_ACCEL 
IMU_SENSOR_TYPE_GYRO 

Definition at line 278 of file AP_InertialSensor.h.

Constructor & Destructor Documentation

◆ AP_InertialSensor() [1/2]

AP_InertialSensor::AP_InertialSensor ( )

Definition at line 455 of file AP_InertialSensor.cpp.

Referenced by get_instance().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ AP_InertialSensor() [2/2]

AP_InertialSensor::AP_InertialSensor ( const AP_InertialSensor other)
delete

Member Function Documentation

◆ _acal_event_failure()

void AP_InertialSensor::_acal_event_failure ( )
privatevirtual

Reimplemented from AP_AccelCal_Client.

Definition at line 1749 of file AP_InertialSensor.cpp.

◆ _acal_get_calibrator()

AccelCalibrator* AP_InertialSensor::_acal_get_calibrator ( uint8_t  i)
inlineprivatevirtual

Implements AP_AccelCal_Client.

Definition at line 569 of file AP_InertialSensor.h.

Here is the call graph for this function:

◆ _acal_save_calibrations()

void AP_InertialSensor::_acal_save_calibrations ( )
privatevirtual

Implements AP_AccelCal_Client.

Definition at line 1685 of file AP_InertialSensor.cpp.

Here is the call graph for this function:

◆ _add_backend()

bool AP_InertialSensor::_add_backend ( AP_InertialSensor_Backend backend)
private

Definition at line 651 of file AP_InertialSensor.cpp.

Referenced by detect_backends().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _calculate_trim()

bool AP_InertialSensor::_calculate_trim ( const Vector3f accel_sample,
float &  trim_roll,
float &  trim_pitch 
)
private

Definition at line 882 of file AP_InertialSensor.cpp.

Referenced by calibrate_trim().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _find_backend()

AP_InertialSensor_Backend * AP_InertialSensor::_find_backend ( int16_t  backend_id,
uint8_t  instance 
)
private

Definition at line 586 of file AP_InertialSensor.cpp.

Referenced by get_auxiliary_bus().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _init_gyro()

void AP_InertialSensor::_init_gyro ( )
private

Definition at line 1078 of file AP_InertialSensor.cpp.

Referenced by init_gyro().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _save_gyro_calibration()

void AP_InertialSensor::_save_gyro_calibration ( )
private

Definition at line 1217 of file AP_InertialSensor.cpp.

Referenced by init_gyro().

Here is the caller graph for this function:

◆ _start_backends()

void AP_InertialSensor::_start_backends ( )
private

Definition at line 563 of file AP_InertialSensor.cpp.

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ acal_init()

void AP_InertialSensor::acal_init ( )

Definition at line 1657 of file AP_InertialSensor.cpp.

Referenced by GCS_MAVLINK::_handle_command_preflight_calibration(), and get_acal().

Here is the caller graph for this function:

◆ acal_update()

void AP_InertialSensor::acal_update ( )

Definition at line 1669 of file AP_InertialSensor.cpp.

Referenced by get_acal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ accel_cal_requires_reboot()

bool AP_InertialSensor::accel_cal_requires_reboot ( ) const
inline

Definition at line 273 of file AP_InertialSensor.h.

Referenced by AP_Arming::ins_checks().

Here is the caller graph for this function:

◆ accel_calibrated_ok_all()

bool AP_InertialSensor::accel_calibrated_ok_all ( ) const

Definition at line 1023 of file AP_InertialSensor.cpp.

Referenced by get_accel_count(), and AP_Arming::ins_checks().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ calc_vibration_and_clipping()

void AP_InertialSensor::calc_vibration_and_clipping ( uint8_t  instance,
const Vector3f accel,
float  dt 
)

Definition at line 1593 of file AP_InertialSensor.cpp.

Referenced by AP_InertialSensor_Backend::_notify_new_accel_raw_sample(), and set_log_raw_bit().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ calibrate_trim()

bool AP_InertialSensor::calibrate_trim ( float &  trim_roll,
float &  trim_pitch 
)

Definition at line 971 of file AP_InertialSensor.cpp.

Here is the call graph for this function:

◆ calibrating()

bool AP_InertialSensor::calibrating ( ) const
inline

calibrating - returns true if the gyros or accels are currently being calibrated

Definition at line 86 of file AP_InertialSensor.h.

Here is the call graph for this function:

◆ detect_backends()

void AP_InertialSensor::detect_backends ( void  )

Definition at line 668 of file AP_InertialSensor.cpp.

Referenced by _start_backends(), get_auxiliary_bus(), and AP_Compass_AK8963::probe_mpu9250().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_acal()

AP_AccelCal* AP_InertialSensor::get_acal ( ) const
inline

Definition at line 252 of file AP_InertialSensor.h.

Referenced by GCS_MAVLINK::_handle_command_preflight_calibration(), and GCS_MAVLINK::handle_command_ack().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_accel() [1/2]

const Vector3f& AP_InertialSensor::get_accel ( uint8_t  i) const
inline

Fetch the current accelerometer values

Returns
vector of current accelerations in m/s/s

Definition at line 124 of file AP_InertialSensor.h.

Referenced by AP_AHRS_DCM::drift_correction(), AP_YawController::get_servo_out(), NavEKF2_core::InitialiseFilterBootstrap(), NavEKF3_core::InitialiseFilterBootstrap(), AP_Arming::ins_checks(), DataFlash_Class::Log_Write_IMU_instance(), AP_AHRS_DCM::reset(), run_test(), GCS_MAVLINK::send_raw_imu(), AP_TECS::update_50hz(), AP_AHRS_NavEKF::update_EKF2(), and AP_AHRS_NavEKF::update_EKF3().

Here is the caller graph for this function:

◆ get_accel() [2/2]

const Vector3f& AP_InertialSensor::get_accel ( void  ) const
inline

Definition at line 125 of file AP_InertialSensor.h.

Referenced by _init_gyro(), calibrate_trim(), get_accel(), get_delta_velocity(), and simple_accel_cal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_accel_clip_count()

uint32_t AP_InertialSensor::get_accel_clip_count ( uint8_t  instance) const

Definition at line 907 of file AP_InertialSensor.cpp.

Referenced by get_vibration_levels(), DataFlash_Class::Log_Write_Vibration(), and GCS_MAVLINK::send_vibration().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_accel_count()

uint8_t AP_InertialSensor::get_accel_count ( void  ) const
inline

Definition at line 143 of file AP_InertialSensor.h.

Referenced by _acal_get_calibrator(), _start_backends(), accel_calibrated_ok_all(), AP_AHRS_DCM::drift_correction(), get_accel_clip_count(), get_accel_health_all(), init(), NavEKF3::InitialiseFilter(), NavEKF2::InitialiseFilter(), AP_Arming::ins_checks(), DataFlash_Class::Log_Write_IMU(), DataFlash_Class::Log_Write_IMUDT(), NavEKF2_core::readDeltaVelocity(), NavEKF3_core::readDeltaVelocity(), run_test(), GCS_MAVLINK::send_raw_imu(), setup(), simple_accel_cal(), AP_AHRS_NavEKF::update_EKF2(), and AP_AHRS_NavEKF::update_EKF3().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_accel_error_count()

uint32_t AP_InertialSensor::get_accel_error_count ( uint8_t  i) const
inline

Definition at line 128 of file AP_InertialSensor.h.

Referenced by DataFlash_Class::Log_Write_IMU_instance().

Here is the caller graph for this function:

◆ get_accel_filter_hz()

uint8_t AP_InertialSensor::get_accel_filter_hz ( void  ) const
inline

Definition at line 213 of file AP_InertialSensor.h.

◆ get_accel_health() [1/2]

bool AP_InertialSensor::get_accel_health ( uint8_t  instance) const
inline

Definition at line 140 of file AP_InertialSensor.h.

Referenced by AP_AHRS_DCM::drift_correction(), DataFlash_Class::Log_Write_IMU_instance(), run_test(), AP_AHRS_NavEKF::update_EKF2(), and AP_AHRS_NavEKF::update_EKF3().

Here is the caller graph for this function:

◆ get_accel_health() [2/2]

bool AP_InertialSensor::get_accel_health ( void  ) const
inline

Definition at line 141 of file AP_InertialSensor.h.

Referenced by calibrate_trim(), get_accel_health(), get_accel_health_all(), get_delta_velocity(), healthy(), and use_accel().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_accel_health_all()

bool AP_InertialSensor::get_accel_health_all ( void  ) const

Definition at line 955 of file AP_InertialSensor.cpp.

Referenced by get_accel_health(), and AP_Arming::ins_checks().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_accel_offsets() [1/2]

const Vector3f& AP_InertialSensor::get_accel_offsets ( uint8_t  i) const
inline

Definition at line 152 of file AP_InertialSensor.h.

Referenced by display_offsets_and_scaling(), and GCS_MAVLINK::send_sensor_offsets().

Here is the caller graph for this function:

◆ get_accel_offsets() [2/2]

const Vector3f& AP_InertialSensor::get_accel_offsets ( void  ) const
inline

Definition at line 153 of file AP_InertialSensor.h.

Referenced by get_accel_offsets().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_accel_peak_hold_neg_x()

float AP_InertialSensor::get_accel_peak_hold_neg_x ( ) const
inline

Definition at line 249 of file AP_InertialSensor.h.

◆ get_accel_rate_hz()

uint16_t AP_InertialSensor::get_accel_rate_hz ( uint8_t  instance) const
inline

Definition at line 149 of file AP_InertialSensor.h.

Referenced by DataFlash_Class::Log_Write_IMU_instance().

Here is the caller graph for this function:

◆ get_accel_scale() [1/2]

const Vector3f& AP_InertialSensor::get_accel_scale ( uint8_t  i) const
inline

Definition at line 156 of file AP_InertialSensor.h.

Referenced by display_offsets_and_scaling().

Here is the caller graph for this function:

◆ get_accel_scale() [2/2]

const Vector3f& AP_InertialSensor::get_accel_scale ( void  ) const
inline

Definition at line 157 of file AP_InertialSensor.h.

Referenced by get_accel_scale().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_auxiliary_bus() [1/2]

AuxiliaryBus* AP_InertialSensor::get_auxiliary_bus ( int16_t  backend_id)
inline

Definition at line 242 of file AP_InertialSensor.h.

Referenced by AP_AK8963_BusDriver_Auxiliary::AP_AK8963_BusDriver_Auxiliary(), and get_auxiliary_bus().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_auxiliary_bus() [2/2]

AuxiliaryBus * AP_InertialSensor::get_auxiliary_bus ( int16_t  backend_id,
uint8_t  instance 
)

Definition at line 1580 of file AP_InertialSensor.cpp.

Here is the call graph for this function:

◆ get_delta_angle() [1/2]

bool AP_InertialSensor::get_delta_angle ( uint8_t  i,
Vector3f delta_angle 
) const

Definition at line 1445 of file AP_InertialSensor.cpp.

Referenced by get_gyro_offsets(), DataFlash_Class::Log_Write_IMUDT_instance(), AP_AHRS_DCM::matrix_update(), NavEKF2_core::readDeltaAngle(), and NavEKF3_core::readDeltaAngle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_delta_angle() [2/2]

bool AP_InertialSensor::get_delta_angle ( Vector3f delta_angle) const
inline

Definition at line 108 of file AP_InertialSensor.h.

Referenced by get_delta_angle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_delta_angle_dt() [1/2]

float AP_InertialSensor::get_delta_angle_dt ( uint8_t  i) const

Definition at line 1492 of file AP_InertialSensor.cpp.

Referenced by DataFlash_Class::Log_Write_IMUDT_instance(), NavEKF2_core::readDeltaAngle(), and NavEKF3_core::readIMUData().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_delta_angle_dt() [2/2]

float AP_InertialSensor::get_delta_angle_dt ( ) const
inline

Definition at line 111 of file AP_InertialSensor.h.

Referenced by get_delta_angle(), and get_delta_angle_dt().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_delta_time()

float AP_InertialSensor::get_delta_time ( ) const
inline

Definition at line 174 of file AP_InertialSensor.h.

Referenced by get_delta_angle(), get_delta_angle_dt(), get_delta_velocity(), get_delta_velocity_dt(), DataFlash_Class::Log_Write_IMUDT_instance(), and AP_AHRS_DCM::update().

Here is the caller graph for this function:

◆ get_delta_velocity() [1/2]

bool AP_InertialSensor::get_delta_velocity ( uint8_t  i,
Vector3f delta_velocity 
) const

Definition at line 1462 of file AP_InertialSensor.cpp.

Referenced by AP_AHRS_DCM::drift_correction(), get_delta_angle_dt(), AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED(), AP_AHRS::getCorrectedDeltaVelocityNED(), DataFlash_Class::Log_Write_IMUDT_instance(), NavEKF2_core::readDeltaVelocity(), and NavEKF3_core::readDeltaVelocity().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_delta_velocity() [2/2]

bool AP_InertialSensor::get_delta_velocity ( Vector3f delta_velocity) const
inline

Definition at line 115 of file AP_InertialSensor.h.

Referenced by get_delta_velocity().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_delta_velocity_dt() [1/2]

float AP_InertialSensor::get_delta_velocity_dt ( uint8_t  i) const

Definition at line 1477 of file AP_InertialSensor.cpp.

Referenced by AP_AHRS_DCM::drift_correction(), AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED(), AP_AHRS::getCorrectedDeltaVelocityNED(), DataFlash_Class::Log_Write_IMUDT_instance(), NavEKF2_core::readDeltaVelocity(), and NavEKF3_core::readDeltaVelocity().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_delta_velocity_dt() [2/2]

float AP_InertialSensor::get_delta_velocity_dt ( ) const
inline

Definition at line 118 of file AP_InertialSensor.h.

Referenced by get_delta_velocity(), and get_delta_velocity_dt().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_fixed_mount_accel_cal_sample()

bool AP_InertialSensor::get_fixed_mount_accel_cal_sample ( uint8_t  sample_num,
Vector3f ret 
) const

Definition at line 1774 of file AP_InertialSensor.cpp.

Referenced by _acal_save_calibrations(), and get_acal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_gyro() [1/2]

const Vector3f& AP_InertialSensor::get_gyro ( uint8_t  i) const
inline

Fetch the current gyro values

Returns
vector of rotational rates in radians/sec

Definition at line 99 of file AP_InertialSensor.h.

Referenced by NavEKF2_core::detectOptFlowTakeoff(), NavEKF3_core::detectOptFlowTakeoff(), AP_AHRS::get_gyro_latest(), AP_Arming::ins_checks(), DataFlash_Class::Log_Write_IMU_instance(), run_test(), GCS_MAVLINK::send_raw_imu(), AP_AHRS_NavEKF::update_EKF2(), and AP_AHRS_NavEKF::update_EKF3().

Here is the caller graph for this function:

◆ get_gyro() [2/2]

const Vector3f& AP_InertialSensor::get_gyro ( void  ) const
inline

Definition at line 100 of file AP_InertialSensor.h.

Referenced by _init_gyro(), get_delta_angle(), and get_gyro().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_gyro_count()

uint8_t AP_InertialSensor::get_gyro_count ( void  ) const
inline

Definition at line 134 of file AP_InertialSensor.h.

Referenced by _init_gyro(), _start_backends(), get_gyro_health_all(), gyro_calibrated_ok_all(), AP_Arming::ins_checks(), DataFlash_Class::Log_Write_IMU(), DataFlash_Class::Log_Write_IMUDT(), AP_AHRS_DCM::matrix_update(), NavEKF2_core::readDeltaAngle(), NavEKF3_core::readDeltaAngle(), run_test(), GCS_MAVLINK::send_raw_imu(), and setup().

Here is the caller graph for this function:

◆ get_gyro_drift_rate()

float AP_InertialSensor::get_gyro_drift_rate ( void  ) const
inline

Definition at line 178 of file AP_InertialSensor.h.

Referenced by AP_AHRS::AP_AHRS().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_gyro_error_count()

uint32_t AP_InertialSensor::get_gyro_error_count ( uint8_t  i) const
inline

Definition at line 127 of file AP_InertialSensor.h.

Referenced by DataFlash_Class::Log_Write_IMU_instance().

Here is the caller graph for this function:

◆ get_gyro_filter_hz()

uint8_t AP_InertialSensor::get_gyro_filter_hz ( void  ) const
inline

Definition at line 210 of file AP_InertialSensor.h.

◆ get_gyro_health() [1/2]

bool AP_InertialSensor::get_gyro_health ( uint8_t  instance) const
inline

Definition at line 131 of file AP_InertialSensor.h.

Referenced by NavEKF2_core::detectOptFlowTakeoff(), NavEKF3_core::detectOptFlowTakeoff(), DataFlash_Class::Log_Write_IMU_instance(), AP_AHRS_DCM::matrix_update(), and run_test().

Here is the caller graph for this function:

◆ get_gyro_health() [2/2]

bool AP_InertialSensor::get_gyro_health ( void  ) const
inline

Definition at line 132 of file AP_InertialSensor.h.

Referenced by get_delta_angle(), get_gyro_health(), get_gyro_health_all(), healthy(), and use_gyro().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_gyro_health_all()

bool AP_InertialSensor::get_gyro_health_all ( void  ) const

Definition at line 916 of file AP_InertialSensor.cpp.

Referenced by get_gyro_health(), and AP_Arming::ins_checks().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_gyro_offsets() [1/2]

const Vector3f& AP_InertialSensor::get_gyro_offsets ( uint8_t  i) const
inline

Definition at line 103 of file AP_InertialSensor.h.

Referenced by display_offsets_and_scaling(), and GCS_MAVLINK::send_sensor_offsets().

Here is the caller graph for this function:

◆ get_gyro_offsets() [2/2]

const Vector3f& AP_InertialSensor::get_gyro_offsets ( void  ) const
inline

Definition at line 104 of file AP_InertialSensor.h.

Referenced by get_gyro_offsets().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_gyro_rate_hz()

uint16_t AP_InertialSensor::get_gyro_rate_hz ( uint8_t  instance) const
inline

Definition at line 148 of file AP_InertialSensor.h.

Referenced by DataFlash_Class::Log_Write_IMU_instance().

Here is the caller graph for this function:

◆ get_imu_pos_offset() [1/2]

const Vector3f& AP_InertialSensor::get_imu_pos_offset ( uint8_t  instance) const
inline

Definition at line 160 of file AP_InertialSensor.h.

Referenced by AC_PrecLand::construct_pos_meas_using_rangefinder(), NavEKF2_core::readIMUData(), NavEKF3_core::readIMUData(), and AC_PrecLand::run_output_prediction().

Here is the caller graph for this function:

◆ get_imu_pos_offset() [2/2]

const Vector3f& AP_InertialSensor::get_imu_pos_offset ( void  ) const
inline

Definition at line 163 of file AP_InertialSensor.h.

◆ get_instance()

AP_InertialSensor * AP_InertialSensor::get_instance ( void  )
static

Definition at line 479 of file AP_InertialSensor.cpp.

Referenced by AP::ins(), and AP_Compass_AK8963::probe_mpu9250().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_last_update_usec()

uint32_t AP_InertialSensor::get_last_update_usec ( void  ) const
inline

Definition at line 276 of file AP_InertialSensor.h.

Referenced by NavEKF3::UpdateFilter(), and NavEKF2::UpdateFilter().

Here is the caller graph for this function:

◆ get_loop_delta_t()

float AP_InertialSensor::get_loop_delta_t ( void  ) const
inline

Definition at line 199 of file AP_InertialSensor.h.

Referenced by NavEKF2_core::InitialiseFilterBootstrap(), NavEKF2_core::InitialiseVariables(), NavEKF3_core::InitialiseVariables(), NavEKF2_core::readIMUData(), and NavEKF3_core::readIMUData().

Here is the caller graph for this function:

◆ get_new_trim()

bool AP_InertialSensor::get_new_trim ( float &  trim_roll,
float &  trim_pitch 
)

Definition at line 1760 of file AP_InertialSensor.cpp.

Referenced by get_acal().

Here is the caller graph for this function:

◆ get_primary_accel()

uint8_t AP_InertialSensor::get_primary_accel ( void  ) const
inline

Definition at line 203 of file AP_InertialSensor.h.

Referenced by AP_AHRS_DCM::drift_correction(), AP_AHRS::get_primary_accel_index(), AP_AHRS_NavEKF::get_primary_accel_index(), AP_AHRS_NavEKF::get_primary_IMU_index(), NavEKF2_core::readIMUData(), NavEKF3_core::readIMUData(), AP_AHRS_NavEKF::update_EKF2(), and AP_AHRS_NavEKF::update_EKF3().

Here is the caller graph for this function:

◆ get_primary_accel_cal_sample_avg()

bool AP_InertialSensor::get_primary_accel_cal_sample_avg ( uint8_t  sample_num,
Vector3f ret 
) const

Definition at line 1791 of file AP_InertialSensor.cpp.

Referenced by _acal_save_calibrations(), and get_acal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_primary_gyro()

uint8_t AP_InertialSensor::get_primary_gyro ( void  ) const
inline

Definition at line 204 of file AP_InertialSensor.h.

Referenced by AP_AHRS::get_primary_gyro_index(), AP_AHRS_NavEKF::get_primary_gyro_index(), NavEKF2_core::readIMUData(), and NavEKF3_core::readIMUData().

Here is the caller graph for this function:

◆ get_sample_rate()

uint16_t AP_InertialSensor::get_sample_rate ( void  ) const
inline

Definition at line 196 of file AP_InertialSensor.h.

Referenced by calibrate_trim(), NavEKF3::InitialiseFilter(), NavEKF2::InitialiseFilter(), and NavEKF3_core::setup_core().

Here is the caller graph for this function:

◆ get_temperature()

float AP_InertialSensor::get_temperature ( uint8_t  instance) const
inline

Definition at line 169 of file AP_InertialSensor.h.

Referenced by DataFlash_Class::Log_Write_IMU_instance(), and run_test().

Here is the caller graph for this function:

◆ get_vibration_levels() [1/2]

Vector3f AP_InertialSensor::get_vibration_levels ( ) const
inline

Definition at line 222 of file AP_InertialSensor.h.

Referenced by get_vibration_levels(), is_still(), DataFlash_Class::Log_Write_Vibration(), and GCS_MAVLINK::send_vibration().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_vibration_levels() [2/2]

Vector3f AP_InertialSensor::get_vibration_levels ( uint8_t  instance) const

Definition at line 1634 of file AP_InertialSensor.cpp.

Here is the call graph for this function:

◆ gyro_calibrated_ok()

bool AP_InertialSensor::gyro_calibrated_ok ( uint8_t  instance) const
inline

Definition at line 135 of file AP_InertialSensor.h.

Referenced by gyro_calibrated_ok_all().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ gyro_calibrated_ok_all()

bool AP_InertialSensor::gyro_calibrated_ok_all ( ) const

Definition at line 928 of file AP_InertialSensor.cpp.

Referenced by gyro_calibrated_ok(), and AP_Arming::ins_checks().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ gyro_calibration_timing()

Gyro_Calibration_Timing AP_InertialSensor::gyro_calibration_timing ( )
inline

Definition at line 138 of file AP_InertialSensor.h.

Referenced by init().

Here is the caller graph for this function:

◆ healthy()

bool AP_InertialSensor::healthy ( void  ) const
inline

Definition at line 201 of file AP_InertialSensor.h.

Referenced by AP_AHRS_DCM::drift_correction().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

void AP_InertialSensor::init ( uint16_t  sample_rate_hz)

Perform startup initialisation.

Called to initialise the state of the IMU.

Gyros will be calibrated unless INS_GYRO_CAL is zero

Parameters
styleThe initialisation startup style.

Definition at line 609 of file AP_InertialSensor.cpp.

Referenced by setup(), and SchedTest::setup().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_gyro()

void AP_InertialSensor::init_gyro ( void  )

Perform cold-start initialisation for just the gyros.

Note
This should not be called unless init has previously been called, as init may perform other work

Definition at line 898 of file AP_InertialSensor.cpp.

Referenced by GCS_MAVLINK::calibrate_gyros(), calibrating(), and init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_still()

bool AP_InertialSensor::is_still ( )

Definition at line 1647 of file AP_InertialSensor.cpp.

Referenced by get_vibration_levels(), and AP_TempCalibration::learn_calibration().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator=()

AP_InertialSensor& AP_InertialSensor::operator= ( const AP_InertialSensor )
delete

◆ periodic()

void AP_InertialSensor::periodic ( )

Definition at line 871 of file AP_InertialSensor.cpp.

Here is the call graph for this function:

◆ register_accel()

uint8_t AP_InertialSensor::register_accel ( uint16_t  raw_sample_rate_hz,
uint32_t  id 
)

Definition at line 524 of file AP_InertialSensor.cpp.

Referenced by AP_InertialSensor_HIL::_init_sensor(), AP_InertialSensor_PX4::_init_sensor(), AP_InertialSensor_SITL::init_sensor(), AP_InertialSensor_LSM9DS0::start(), AP_InertialSensor_LSM9DS1::start(), AP_InertialSensor_L3G4200D::start(), AP_InertialSensor_BMI160::start(), AP_InertialSensor_RST::start(), and AP_InertialSensor_Invensense::start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ register_gyro()

uint8_t AP_InertialSensor::register_gyro ( uint16_t  raw_sample_rate_hz,
uint32_t  id 
)

Register a new gyro/accel driver, allocating an instance number

Definition at line 490 of file AP_InertialSensor.cpp.

Referenced by AP_InertialSensor_HIL::_init_sensor(), AP_InertialSensor_PX4::_init_sensor(), AP_InertialSensor_SITL::init_sensor(), AP_InertialSensor_LSM9DS0::start(), AP_InertialSensor_LSM9DS1::start(), AP_InertialSensor_L3G4200D::start(), AP_InertialSensor_BMI160::start(), AP_InertialSensor_RST::start(), and AP_InertialSensor_Invensense::start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_accel()

void AP_InertialSensor::set_accel ( uint8_t  instance,
const Vector3f accel 
)

Definition at line 1508 of file AP_InertialSensor.cpp.

Referenced by get_vibration_levels().

Here is the caller graph for this function:

◆ set_accel_peak_hold()

void AP_InertialSensor::set_accel_peak_hold ( uint8_t  instance,
const Vector3f accel 
)

Definition at line 1617 of file AP_InertialSensor.cpp.

Referenced by AP_InertialSensor_Backend::_notify_new_accel_raw_sample(), and get_auxiliary_bus().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_board_orientation()

void AP_InertialSensor::set_board_orientation ( enum Rotation  orientation,
Matrix3f custom_rotation = nullptr 
)
inline

Definition at line 190 of file AP_InertialSensor.h.

Referenced by AP_AHRS::set_orientation().

Here is the caller graph for this function:

◆ set_delta_angle()

void AP_InertialSensor::set_delta_angle ( uint8_t  instance,
const Vector3f deltaa,
float  deltaat 
)

Definition at line 1568 of file AP_InertialSensor.cpp.

Referenced by get_vibration_levels().

Here is the caller graph for this function:

◆ set_delta_time()

void AP_InertialSensor::set_delta_time ( float  delta_time)

Definition at line 1548 of file AP_InertialSensor.cpp.

Referenced by get_vibration_levels().

Here is the caller graph for this function:

◆ set_delta_velocity()

void AP_InertialSensor::set_delta_velocity ( uint8_t  instance,
float  deltavt,
const Vector3f deltav 
)

Definition at line 1556 of file AP_InertialSensor.cpp.

Referenced by get_vibration_levels().

Here is the caller graph for this function:

◆ set_gyro()

void AP_InertialSensor::set_gyro ( uint8_t  instance,
const Vector3f gyro 
)

Definition at line 1526 of file AP_InertialSensor.cpp.

Referenced by get_vibration_levels().

Here is the caller graph for this function:

◆ set_hil_mode()

void AP_InertialSensor::set_hil_mode ( void  )
inline

Definition at line 207 of file AP_InertialSensor.h.

Referenced by AP_InertialSensor_HIL::_init_sensor().

Here is the caller graph for this function:

◆ set_log_raw_bit()

void AP_InertialSensor::set_log_raw_bit ( uint32_t  log_raw_bit)
inline

Definition at line 216 of file AP_InertialSensor.h.

Here is the call graph for this function:

◆ simple_accel_cal()

MAV_RESULT AP_InertialSensor::simple_accel_cal ( )

Definition at line 1820 of file AP_InertialSensor.cpp.

Referenced by GCS_MAVLINK::_handle_command_preflight_calibration(), and get_acal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update()

void AP_InertialSensor::update ( void  )

Definition at line 1233 of file AP_InertialSensor.cpp.

Referenced by _init_gyro(), calibrate_trim(), get_gyro_drift_rate(), SchedTest::ins_update(), AP_AHRS_DCM::reset(), run_test(), simple_accel_cal(), and AP_AHRS_DCM::update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ use_accel()

bool AP_InertialSensor::use_accel ( uint8_t  instance) const

Definition at line 1068 of file AP_InertialSensor.cpp.

Referenced by AP_AHRS_DCM::drift_correction(), get_accel_count(), AP_Arming::ins_checks(), NavEKF2_core::readIMUData(), and NavEKF3_core::readIMUData().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ use_gyro()

bool AP_InertialSensor::use_gyro ( uint8_t  instance) const

Definition at line 945 of file AP_InertialSensor.cpp.

Referenced by gyro_calibrated_ok(), AP_Arming::ins_checks(), DataFlash_Class::Log_Write_IMUDT(), NavEKF2_core::readIMUData(), and NavEKF3_core::readIMUData().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ wait_for_sample()

void AP_InertialSensor::wait_for_sample ( void  )

Definition at line 1343 of file AP_InertialSensor.cpp.

Referenced by calibrate_trim(), get_gyro_drift_rate(), AP_Scheduler::loop(), AP_AHRS_DCM::reset(), run_test(), and update().

Here is the call graph for this function:
Here is the caller graph for this function:

Friends And Related Function Documentation

◆ AP_InertialSensor_Backend

friend class AP_InertialSensor_Backend
friend

Definition at line 49 of file AP_InertialSensor.h.

Member Data Documentation

◆ _acal

AP_AccelCal* AP_InertialSensor::_acal
private

Definition at line 560 of file AP_InertialSensor.h.

Referenced by acal_init(), acal_update(), and get_acal().

◆ _acc_body_aligned

AP_Int8 AP_InertialSensor::_acc_body_aligned
private

Definition at line 556 of file AP_InertialSensor.h.

Referenced by get_fixed_mount_accel_cal_sample().

◆ _accel

Vector3f AP_InertialSensor::_accel[INS_MAX_INSTANCES]
private

◆ _accel_cal_requires_reboot

bool AP_InertialSensor::_accel_cal_requires_reboot
private

Definition at line 575 of file AP_InertialSensor.h.

Referenced by _acal_save_calibrations(), and accel_cal_requires_reboot().

◆ _accel_calibrator

AccelCalibrator* AP_InertialSensor::_accel_calibrator
private

◆ _accel_clip_count

uint32_t AP_InertialSensor::_accel_clip_count[INS_MAX_INSTANCES]
private

◆ _accel_count

uint8_t AP_InertialSensor::_accel_count
private

◆ _accel_error_count

uint32_t AP_InertialSensor::_accel_error_count[INS_MAX_INSTANCES]
private

◆ _accel_filter

LowPassFilter2pVector3f AP_InertialSensor::_accel_filter[INS_MAX_INSTANCES]
private

◆ _accel_filter_cutoff

AP_Int8 AP_InertialSensor::_accel_filter_cutoff
private

◆ _accel_filtered

Vector3f AP_InertialSensor::_accel_filtered[INS_MAX_INSTANCES]
private

◆ _accel_healthy

bool AP_InertialSensor::_accel_healthy[INS_MAX_INSTANCES]
private

◆ _accel_id

AP_Int32 AP_InertialSensor::_accel_id[INS_MAX_INSTANCES]
private

◆ _accel_id_ok

bool AP_InertialSensor::_accel_id_ok[INS_MAX_INSTANCES]
private

◆ _accel_last_sample_us

uint64_t AP_InertialSensor::_accel_last_sample_us[INS_MAX_INSTANCES]
private

◆ _accel_max_abs_offsets

float AP_InertialSensor::_accel_max_abs_offsets[INS_MAX_INSTANCES]
private

◆ _accel_offset

AP_Vector3f AP_InertialSensor::_accel_offset[INS_MAX_INSTANCES]
private

◆ _accel_orientation

enum Rotation AP_InertialSensor::_accel_orientation[INS_MAX_INSTANCES]
private

◆ _accel_over_sampling

uint8_t AP_InertialSensor::_accel_over_sampling[INS_MAX_INSTANCES]
private

◆ _accel_pos

AP_Vector3f AP_InertialSensor::_accel_pos[INS_MAX_INSTANCES]
private

Definition at line 441 of file AP_InertialSensor.h.

Referenced by get_imu_pos_offset().

◆ _accel_raw_sample_rates

float AP_InertialSensor::_accel_raw_sample_rates[INS_MAX_INSTANCES]
private

◆ _accel_raw_sampling_multiplier

uint16_t AP_InertialSensor::_accel_raw_sampling_multiplier[INS_MAX_INSTANCES]
private

◆ _accel_scale

AP_Vector3f AP_InertialSensor::_accel_scale[INS_MAX_INSTANCES]
private

◆ _accel_sensor_rate_sampling_enabled

uint8_t AP_InertialSensor::_accel_sensor_rate_sampling_enabled
private

◆ _accel_startup_error_count

uint32_t AP_InertialSensor::_accel_startup_error_count[INS_MAX_INSTANCES]
private

Definition at line 578 of file AP_InertialSensor.h.

Referenced by update().

◆ _accel_vibe_filter

LowPassFilterVector3f AP_InertialSensor::_accel_vibe_filter[INS_VIBRATION_CHECK_INSTANCES]
private

◆ _accel_vibe_floor_filter

LowPassFilterVector3f AP_InertialSensor::_accel_vibe_floor_filter[INS_VIBRATION_CHECK_INSTANCES]
private

Definition at line 536 of file AP_InertialSensor.h.

Referenced by AP_InertialSensor(), and calc_vibration_and_clipping().

◆ _backend_count

uint8_t AP_InertialSensor::_backend_count
private

◆ _backends

AP_InertialSensor_Backend* AP_InertialSensor::_backends[INS_MAX_BACKENDS]
private

◆ _backends_detected

bool AP_InertialSensor::_backends_detected
private

Definition at line 510 of file AP_InertialSensor.h.

Referenced by _find_backend(), and detect_backends().

◆ _board_orientation

enum Rotation AP_InertialSensor::_board_orientation
private

◆ _calibrating

bool AP_InertialSensor::_calibrating
private

Definition at line 508 of file AP_InertialSensor.h.

Referenced by _init_gyro(), calibrate_trim(), calibrating(), and simple_accel_cal().

◆ _custom_rotation

Matrix3f* AP_InertialSensor::_custom_rotation
private

◆ _delta_angle

Vector3f AP_InertialSensor::_delta_angle[INS_MAX_INSTANCES]
private

◆ _delta_angle_acc

Vector3f AP_InertialSensor::_delta_angle_acc[INS_MAX_INSTANCES]
private

◆ _delta_angle_acc_dt

float AP_InertialSensor::_delta_angle_acc_dt[INS_MAX_INSTANCES]
private

◆ _delta_angle_dt

float AP_InertialSensor::_delta_angle_dt[INS_MAX_INSTANCES]
private

◆ _delta_angle_valid

bool AP_InertialSensor::_delta_angle_valid[INS_MAX_INSTANCES]
private

◆ _delta_time

float AP_InertialSensor::_delta_time
private

Definition at line 513 of file AP_InertialSensor.h.

Referenced by get_delta_time(), init(), and wait_for_sample().

◆ _delta_velocity

Vector3f AP_InertialSensor::_delta_velocity[INS_MAX_INSTANCES]
private

◆ _delta_velocity_acc

Vector3f AP_InertialSensor::_delta_velocity_acc[INS_MAX_INSTANCES]
private

◆ _delta_velocity_acc_dt

float AP_InertialSensor::_delta_velocity_acc_dt[INS_MAX_INSTANCES]
private

◆ _delta_velocity_dt

float AP_InertialSensor::_delta_velocity_dt[INS_MAX_INSTANCES]
private

◆ _delta_velocity_valid

bool AP_InertialSensor::_delta_velocity_valid[INS_MAX_INSTANCES]
private

◆ _enable_mask

AP_Int8 AP_InertialSensor::_enable_mask
private

Definition at line 480 of file AP_InertialSensor.h.

Referenced by detect_backends().

◆ _fast_sampling_mask

AP_Int8 AP_InertialSensor::_fast_sampling_mask
private

◆ _gyro

Vector3f AP_InertialSensor::_gyro[INS_MAX_INSTANCES]
private

◆ _gyro_cal_ok

bool AP_InertialSensor::_gyro_cal_ok[INS_MAX_INSTANCES]
private

◆ _gyro_cal_timing

AP_Int8 AP_InertialSensor::_gyro_cal_timing
private

Definition at line 471 of file AP_InertialSensor.h.

Referenced by gyro_calibration_timing().

◆ _gyro_count

uint8_t AP_InertialSensor::_gyro_count
private

◆ _gyro_error_count

uint32_t AP_InertialSensor::_gyro_error_count[INS_MAX_INSTANCES]
private

◆ _gyro_filter

LowPassFilter2pVector3f AP_InertialSensor::_gyro_filter[INS_MAX_INSTANCES]
private

◆ _gyro_filter_cutoff

AP_Int8 AP_InertialSensor::_gyro_filter_cutoff
private

◆ _gyro_filtered

Vector3f AP_InertialSensor::_gyro_filtered[INS_MAX_INSTANCES]
private

◆ _gyro_healthy

bool AP_InertialSensor::_gyro_healthy[INS_MAX_INSTANCES]
private

◆ _gyro_id

AP_Int32 AP_InertialSensor::_gyro_id[INS_MAX_INSTANCES]
private

◆ _gyro_last_sample_us

uint64_t AP_InertialSensor::_gyro_last_sample_us[INS_MAX_INSTANCES]
private

◆ _gyro_offset

AP_Vector3f AP_InertialSensor::_gyro_offset[INS_MAX_INSTANCES]
private

◆ _gyro_orientation

enum Rotation AP_InertialSensor::_gyro_orientation[INS_MAX_INSTANCES]
private

◆ _gyro_over_sampling

uint8_t AP_InertialSensor::_gyro_over_sampling[INS_MAX_INSTANCES]
private

◆ _gyro_raw_sample_rates

float AP_InertialSensor::_gyro_raw_sample_rates[INS_MAX_INSTANCES]
private

◆ _gyro_raw_sampling_multiplier

uint16_t AP_InertialSensor::_gyro_raw_sampling_multiplier[INS_MAX_INSTANCES]
private

◆ _gyro_sensor_rate_sampling_enabled

uint8_t AP_InertialSensor::_gyro_sensor_rate_sampling_enabled
private

◆ _gyro_startup_error_count

uint32_t AP_InertialSensor::_gyro_startup_error_count[INS_MAX_INSTANCES]
private

Definition at line 579 of file AP_InertialSensor.h.

Referenced by update().

◆ _have_sample

bool AP_InertialSensor::_have_sample
private

Definition at line 502 of file AP_InertialSensor.h.

Referenced by init(), update(), and wait_for_sample().

◆ _hil

struct { ... } AP_InertialSensor::_hil

Referenced by set_delta_time(), and wait_for_sample().

◆ _hil_mode

bool AP_InertialSensor::_hil_mode
private

◆ _last_delta_angle

Vector3f AP_InertialSensor::_last_delta_angle[INS_MAX_INSTANCES]
private

◆ _last_raw_gyro

Vector3f AP_InertialSensor::_last_raw_gyro[INS_MAX_INSTANCES]
private

◆ _last_sample_usec

uint32_t AP_InertialSensor::_last_sample_usec
private

Definition at line 516 of file AP_InertialSensor.h.

Referenced by init(), and wait_for_sample().

◆ _last_update_usec

uint32_t AP_InertialSensor::_last_update_usec
private

Definition at line 525 of file AP_InertialSensor.h.

Referenced by get_last_update_usec(), and update().

◆ _log_raw_bit

uint32_t AP_InertialSensor::_log_raw_bit
private

◆ _loop_delta_t

float AP_InertialSensor::_loop_delta_t
private

Definition at line 384 of file AP_InertialSensor.h.

Referenced by get_loop_delta_t(), and init().

◆ _loop_delta_t_max

float AP_InertialSensor::_loop_delta_t_max
private

◆ _new_accel_data

bool AP_InertialSensor::_new_accel_data[INS_MAX_INSTANCES]
private

◆ _new_gyro_data

bool AP_InertialSensor::_new_gyro_data[INS_MAX_INSTANCES]
private

◆ _new_trim

bool AP_InertialSensor::_new_trim
private

Definition at line 573 of file AP_InertialSensor.h.

Referenced by _acal_save_calibrations(), and get_new_trim().

◆ _next_sample_usec

uint32_t AP_InertialSensor::_next_sample_usec
private

Definition at line 519 of file AP_InertialSensor.h.

Referenced by init(), and wait_for_sample().

◆ _notch_filter

NotchFilterVector3fParam AP_InertialSensor::_notch_filter
private

Definition at line 406 of file AP_InertialSensor.h.

Referenced by init(), and update().

◆ _old_product_id

AP_Int16 AP_InertialSensor::_old_product_id
private

Definition at line 428 of file AP_InertialSensor.h.

◆ _peak_hold_state

struct AP_InertialSensor::PeakHoldState AP_InertialSensor::_peak_hold_state
private

◆ _primary_accel

uint8_t AP_InertialSensor::_primary_accel
private

◆ _primary_gyro

uint8_t AP_InertialSensor::_primary_gyro
private

◆ _s_instance

AP_InertialSensor * AP_InertialSensor::_s_instance = nullptr
staticprivate

Definition at line 559 of file AP_InertialSensor.h.

Referenced by AP_InertialSensor(), and get_instance().

◆ _sample_accel_count

uint16_t AP_InertialSensor::_sample_accel_count[INS_MAX_INSTANCES]
private

◆ _sample_accel_start_us

uint32_t AP_InertialSensor::_sample_accel_start_us[INS_MAX_INSTANCES]
private

◆ _sample_gyro_count

uint16_t AP_InertialSensor::_sample_gyro_count[INS_MAX_INSTANCES]
private

◆ _sample_gyro_start_us

uint32_t AP_InertialSensor::_sample_gyro_start_us[INS_MAX_INSTANCES]
private

◆ _sample_period_usec

uint32_t AP_InertialSensor::_sample_period_usec
private

Definition at line 522 of file AP_InertialSensor.h.

Referenced by init(), and wait_for_sample().

◆ _sample_rate

uint16_t AP_InertialSensor::_sample_rate
private

◆ _startup_error_counts_set

bool AP_InertialSensor::_startup_error_counts_set
private

Definition at line 580 of file AP_InertialSensor.h.

Referenced by update().

◆ _startup_ms

uint32_t AP_InertialSensor::_startup_ms
private

Definition at line 581 of file AP_InertialSensor.h.

Referenced by update().

◆ _still_threshold

AP_Float AP_InertialSensor::_still_threshold
private

Definition at line 546 of file AP_InertialSensor.h.

Referenced by is_still().

◆ _temperature

float AP_InertialSensor::_temperature[INS_MAX_INSTANCES]
private

◆ _trim_option

AP_Int8 AP_InertialSensor::_trim_option
private

Definition at line 557 of file AP_InertialSensor.h.

Referenced by _acal_save_calibrations().

◆ _trim_pitch

float AP_InertialSensor::_trim_pitch
private

Definition at line 571 of file AP_InertialSensor.h.

Referenced by _acal_save_calibrations(), and get_new_trim().

◆ _trim_roll

float AP_InertialSensor::_trim_roll
private

Definition at line 572 of file AP_InertialSensor.h.

Referenced by _acal_save_calibrations(), and get_new_trim().

◆ _use

AP_Int8 AP_InertialSensor::_use[INS_MAX_INSTANCES]
private

Definition at line 474 of file AP_InertialSensor.h.

Referenced by update(), use_accel(), and use_gyro().

◆ batchsampler

BatchSampler AP_InertialSensor::batchsampler {*this}

◆ delta_time

float AP_InertialSensor::delta_time

Definition at line 552 of file AP_InertialSensor.h.

Referenced by get_vibration_levels(), and set_delta_time().

◆ var_info

const AP_Param::GroupInfo AP_InertialSensor::var_info
static

Definition at line 187 of file AP_InertialSensor.h.

Referenced by AP_InertialSensor().


The documentation for this class was generated from the following files: