28 #ifdef INS_TIMING_DEBUG 30 #define timing_printf(fmt, args...) do { printf("[timing] " fmt, ##args); } while(0) 32 #define timing_printf(fmt, args...) 37 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) 38 #define DEFAULT_GYRO_FILTER 20 39 #define DEFAULT_ACCEL_FILTER 20 40 #define DEFAULT_STILL_THRESH 2.5f 41 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2) 42 #define DEFAULT_GYRO_FILTER 4 43 #define DEFAULT_ACCEL_FILTER 10 44 #define DEFAULT_STILL_THRESH 0.1f 46 #define DEFAULT_GYRO_FILTER 20 47 #define DEFAULT_ACCEL_FILTER 20 48 #define DEFAULT_STILL_THRESH 0.1f 53 #define GYRO_INIT_MAX_DIFF_DPS 0.1f 510 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_SITL 549 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_SITL 594 if (
id < 0 ||
id != backend_id) {
598 if (instance == found) {
676 uint8_t probe_count = 0;
678 uint8_t found_mask = 0;
683 #define ADD_BACKEND(x) do { \ 684 if (((1U<<probe_count)&enable_mask) && _add_backend(x)) { \ 685 found_mask |= (1U<<probe_count); \ 694 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 696 #elif HAL_INS_DEFAULT == HAL_INS_HIL 698 #elif CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT 700 #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_SPI && defined(HAL_INS_DEFAULT_ROTATION) 703 #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_SPI 705 #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_I2C && defined(HAL_INS_DEFAULT_ROTATION) 708 #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_I2C 710 #elif HAL_INS_DEFAULT == HAL_INS_BH 713 #elif AP_FEATURE_BOARD_DETECT 799 #ifdef HAL_INS_MPU60x0_IMU_NAME 820 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 824 #elif HAL_INS_DEFAULT == HAL_INS_MPU9250_SPI && defined(HAL_INS_DEFAULT_ROTATION) 826 #elif HAL_INS_DEFAULT == HAL_INS_MPU9250_SPI 828 #elif HAL_INS_DEFAULT == HAL_INS_EDGE 831 #elif HAL_INS_DEFAULT == HAL_INS_LSM9DS1 833 #elif HAL_INS_DEFAULT == HAL_INS_LSM9DS0 837 #elif HAL_INS_DEFAULT == HAL_INS_L3G4200D 839 #elif HAL_INS_DEFAULT == HAL_INS_MPU9250_I2C 841 #elif HAL_INS_DEFAULT == HAL_INS_BBBMINI 844 #elif HAL_INS_DEFAULT == HAL_INS_AERO 846 #elif HAL_INS_DEFAULT == HAL_INS_RST 849 HAL_INS_DEFAULT_G_ROTATION,
850 HAL_INS_DEFAULT_A_ROTATION));
851 #elif HAL_INS_DEFAULT == HAL_INS_ICM20789_SPI 853 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSF7V2 856 #elif HAL_INS_DEFAULT == HAL_INS_NONE 859 #error Unrecognised HAL_INS_TYPE setting 884 trim_pitch = atan2f(accel_sample.
x,
norm(accel_sample.
y, accel_sample.
z));
885 trim_roll = atan2f(-accel_sample.
y, -accel_sample.
z);
886 if (fabsf(trim_roll) >
radians(10) ||
887 fabsf(trim_pitch) >
radians(10)) {
982 const uint8_t update_dt_milliseconds = (uint8_t)(1000.0
f/
get_sample_rate()+0.5f);
985 for (uint8_t k=0; k<100/update_dt_milliseconds; k++) {
991 uint32_t num_samples = 0;
992 while (num_samples < 400/update_dt_milliseconds) {
999 level_sample += samp;
1006 level_sample /= num_samples;
1057 if (have_scaling || have_offsets) {
1108 for (uint8_t k=0; k<num_gyros; k++) {
1110 new_gyro_offset[k].
zero();
1111 best_diff[k] = -1.f;
1112 last_average[k].
zero();
1113 converged[k] =
false;
1116 for(int8_t c = 0; c < 5; c++) {
1125 uint8_t num_converged = 0;
1129 for (int16_t j = 0; j <= 30*4 && num_converged < num_gyros; j++) {
1135 memset(diff_norm, 0,
sizeof(diff_norm));
1139 for (uint8_t k=0; k<num_gyros; k++) {
1143 for (i=0; i<50; i++) {
1145 for (uint8_t k=0; k<num_gyros; k++) {
1152 if (accel_diff.
length() > 0.2f) {
1160 for (uint8_t k=0; k<num_gyros; k++) {
1161 gyro_avg[k] = gyro_sum[k] / i;
1162 gyro_diff[k] = last_average[k] - gyro_avg[k];
1163 diff_norm[k] = gyro_diff[k].
length();
1166 for (uint8_t k=0; k<num_gyros; k++) {
1167 if (best_diff[k] < 0) {
1168 best_diff[k] = diff_norm[k];
1169 best_avg[k] = gyro_avg[k];
1172 last_average[k] = (gyro_avg[k] * 0.5f) + (last_average[k] * 0.5
f);
1173 if (!converged[k] || last_average[k].length() < new_gyro_offset[k].
length()) {
1174 new_gyro_offset[k] = last_average[k];
1176 if (!converged[k]) {
1177 converged[k] =
true;
1180 }
else if (diff_norm[k] < best_diff[k]) {
1181 best_diff[k] = diff_norm[k];
1182 best_avg[k] = (gyro_avg[k] * 0.5f) + (last_average[k] * 0.5
f);
1184 last_average[k] = gyro_avg[k];
1191 for (uint8_t k=0; k<num_gyros; k++) {
1192 if (!converged[k]) {
1193 hal.
console->
printf(
"gyro[%u] did not converge: diff=%f dps (expected < %f)\n",
1195 (
double)
ToDeg(best_diff[k]),
1285 bool have_zero_accel_error_count =
false;
1286 bool have_zero_gyro_error_count =
false;
1289 have_zero_accel_error_count =
true;
1292 have_zero_gyro_error_count =
true;
1372 (
unsigned)wait_usec);
1391 bool gyro_available =
false;
1392 bool accel_available =
false;
1403 if (gyro_available && accel_available) {
1414 _hil.delta_time = 0;
1422 static uint64_t delta_time_sum;
1424 if (delta_time_sum == 0) {
1428 if (counter++ == 400) {
1430 hal.
console->
printf(
"now=%lu _delta_time_sum=%lu diff=%ld\n",
1432 (
unsigned long)delta_time_sum,
1433 (
long)(now - delta_time_sum));
1515 _accel[instance] = accel;
1521 _primary_accel = instance;
1533 _gyro[instance] = gyro;
1540 _primary_accel = instance;
1585 if (backend ==
nullptr) {
1608 Vector3f accel_diff = (accel - accel_filt);
1609 accel_diff.
x *= accel_diff.
x;
1610 accel_diff.
y *= accel_diff.
y;
1611 accel_diff.
z *= accel_diff.
z;
1660 if (
_acal ==
nullptr) {
1671 if(
_acal ==
nullptr) {
1718 _trim_roll = atan2f(-aligned_sample.
y, -aligned_sample.
z);
1726 Vector3f cross = (misaligned_sample%aligned_sample);
1727 float dot = (misaligned_sample*aligned_sample);
1742 hal.
console->
printf(
"ERR: Trim over maximum of 10 degrees!!");
1828 const float accel_convergence_limit = 0.05;
1833 return MAV_RESULT_TEMPORARILY_REJECTED;
1855 for (uint8_t k=0; k<num_accels; k++) {
1861 for (uint8_t k=0; k<num_accels; k++) {
1864 new_accel_offset[k].
zero();
1865 last_average[k].
zero();
1866 converged[k] =
false;
1869 for (uint8_t c = 0; c < 5; c++) {
1878 uint8_t num_converged = 0;
1882 for (int16_t j = 0; j <= 10*4 && num_converged < num_accels; j++) {
1887 memset(diff_norm, 0,
sizeof(diff_norm));
1891 for (uint8_t k=0; k<num_accels; k++) {
1892 accel_sum[k].
zero();
1894 for (i=0; i<50; i++) {
1896 for (uint8_t k=0; k<num_accels; k++) {
1902 for (uint8_t k=0; k<num_accels; k++) {
1903 accel_avg[k] = accel_sum[k] / i;
1904 accel_diff[k] = last_average[k] - accel_avg[k];
1905 diff_norm[k] = accel_diff[k].
length();
1908 for (uint8_t k=0; k<num_accels; k++) {
1909 if (j > 0 && diff_norm[k] < accel_convergence_limit) {
1910 last_average[k] = (accel_avg[k] * 0.5f) + (last_average[k] * 0.5
f);
1911 if (!converged[k] || last_average[k].length() < new_accel_offset[k].
length()) {
1912 new_accel_offset[k] = last_average[k];
1914 if (!converged[k]) {
1915 converged[k] =
true;
1919 last_average[k] = accel_avg[k];
1924 MAV_RESULT
result = MAV_RESULT_ACCEPTED;
1927 for (uint8_t k=0; k<num_accels; k++) {
1928 if (!converged[k]) {
1929 result = MAV_RESULT_FAILED;
1936 if (result == MAV_RESULT_ACCEPTED) {
1938 for (uint8_t k=0; k<num_accels; k++) {
1940 new_accel_offset[k] -= rotated_gravity;
1952 for (uint8_t k=0; k<num_accels; k++) {
float norm(const T first, const U second, const Params... parameters)
bool get_sample_corrected(uint8_t i, Vector3f &s) const
bool get_soft_armed() const
#define HAL_INS_MPU60x0_IMU_NAME
struct AP_InertialSensor::@119 _hil
void set_delta_velocity(uint8_t instance, float deltavt, const Vector3f &deltav)
#define HAL_INS_MPU9250_EXT_NAME
uint32_t _accel_startup_error_count[INS_MAX_INSTANCES]
void set_delta_time(float delta_time)
uint32_t _next_sample_usec
#define AP_INERTIAL_SENSOR_ACCEL_PEAK_DETECT_TIMEOUT_MS
Vector3< float > Vector3f
uint32_t _accel_error_count[INS_MAX_INSTANCES]
static AP_InertialSensor * _s_instance
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
void _acal_save_calibrations()
static enum px4_board_type get_board_type(void)
const Vector3f & get_accel(void) const
float safe_sqrt(const T v)
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
bool _gyro_healthy[INS_MAX_INSTANCES]
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
#define GYRO_INIT_MAX_DIFF_DPS
bool _new_gyro_data[INS_MAX_INSTANCES]
AP_HAL::UARTDriver * console
AP_Float _still_threshold
void rotate_inverse(enum Rotation rotation)
#define HAL_INS_LSM9DS0_A_NAME
uint32_t _last_update_usec
void init(float sample_freq_hz)
void _acal_event_failure()
AP_Int8 _use[INS_MAX_INSTANCES]
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
#define AP_GROUPINFO(name, idx, clazz, element, def)
float _accel_raw_sample_rates[INS_MAX_INSTANCES]
Vector3f apply(const Vector3f &sample)
void set_delta_angle(uint8_t instance, const Vector3f &deltaa, float deltaat)
AP_InertialSensor_Backend * _backends[INS_MAX_BACKENDS]
LowPassFilterVector3f _accel_vibe_floor_filter[INS_VIBRATION_CHECK_INSTANCES]
void _save_gyro_calibration()
virtual void reset(bool recover_eulers=false)=0
static const struct AP_Param::GroupInfo var_info[]
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev, enum Rotation rotation=ROTATION_NONE)
bool gyro_calibrated_ok(uint8_t instance) const
bool _delta_angle_valid[INS_MAX_INSTANCES]
float _delta_velocity_dt[INS_MAX_INSTANCES]
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
const Vector3f & get_gyro(void) const
float _delta_velocity_acc_dt[INS_MAX_INSTANCES]
bool _add_backend(AP_InertialSensor_Backend *backend)
#define HAL_INS_MPU60x0_EXT_NAME
bool use_accel(uint8_t instance) const
#define DEFAULT_STILL_THRESH
#define AP_INERTIAL_SENSOR_ACCEL_VIBE_FLOOR_FILT_HZ
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a=ROTATION_NONE, enum Rotation rotation_g=ROTATION_NONE, enum Rotation rotation_gH=ROTATION_NONE)
Matrix3f * _custom_rotation
float _accel_max_abs_offsets[INS_MAX_INSTANCES]
AP_Int8 _fast_sampling_mask
void get_calibration(Vector3f &offset) const
uint16_t _accel_raw_sampling_multiplier[INS_MAX_INSTANCES]
static void register_client(AP_AccelCal_Client *client)
void set_cutoff_frequency(float cutoff_freq)
#define DEFAULT_GYRO_FILTER
#define HAL_INS_ICM20608_AM_NAME
uint8_t get_num_samples_collected() const
Vector3f _delta_angle_acc[INS_MAX_INSTANCES]
float _gyro_raw_sample_rates[INS_MAX_INSTANCES]
#define INS_VIBRATION_CHECK_INSTANCES
virtual void delay(uint16_t ms)=0
bool _accel_id_ok[INS_MAX_INSTANCES]
AP_Vector3f _accel_scale[INS_MAX_INSTANCES]
bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const
Vector3f _delta_angle[INS_MAX_INSTANCES]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
AP_InertialSensor_Backend * _find_backend(int16_t backend_id, uint8_t instance)
AP_Int32 _gyro_id[INS_MAX_INSTANCES]
bool _new_accel_data[INS_MAX_INSTANCES]
virtual void printf(const char *,...) FMT_PRINTF(2
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
virtual void set_trim(Vector3f new_trim)
virtual OwnPtr< SPIDevice > get_device(const char *name)
uint8_t _gyro_over_sampling[INS_MAX_INSTANCES]
bool get_accel_health_all(void) const
accel_cal_status_t get_status()
bool _calculate_trim(const Vector3f &accel_sample, float &trim_roll, float &trim_pitch)
bool use_gyro(uint8_t instance) const
#define HAL_INS_MPU60x0_NAME
bool _startup_error_counts_set
bool is_zero(const T fVal1)
uint32_t _gyro_error_count[INS_MAX_INSTANCES]
uint32_t _sample_period_usec
bool _accel_cal_requires_reboot
#define timing_printf(fmt, args...)
void set_accel(uint8_t instance, const Vector3f &accel)
virtual AuxiliaryBus * get_auxiliary_bus()
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
AP_Int32 _accel_id[INS_MAX_INSTANCES]
LowPassFilterVector3f _accel_vibe_filter[INS_VIBRATION_CHECK_INSTANCES]
float _delta_angle_acc_dt[INS_MAX_INSTANCES]
#define HAL_INS_LSM9DS0_EXT_A_NAME
#define DEFAULT_ACCEL_FILTER
bool _gyro_cal_ok[INS_MAX_INSTANCES]
uint32_t get_accel_clip_count(uint8_t instance) const
bool _delta_velocity_valid[INS_MAX_INSTANCES]
#define HAL_INS_ICM20608_NAME
AP_HAL::SPIDeviceManager * spi
#define HAL_INS_MPU9250_NAME
Vector3f _gyro[INS_MAX_INSTANCES]
uint16_t get_sample_rate(void) const
MAV_RESULT simple_accel_cal()
Vector3f _delta_velocity[INS_MAX_INSTANCES]
Gyro_Calibration_Timing gyro_calibration_timing()
void set_accel_peak_hold(uint8_t instance, const Vector3f &accel)
bool get_gyro_health(void) const
float get_delta_time() const
bool get_primary_accel_cal_sample_avg(uint8_t sample_num, Vector3f &ret) const
uint16_t _gyro_raw_sampling_multiplier[INS_MAX_INSTANCES]
bool calibrate_trim(float &trim_roll, float &trim_pitch)
AP_HAL::I2CDeviceManager * i2c_mgr
bool get_accel_health(void) const
void rotate(enum Rotation rotation)
enum Rotation _board_orientation
Common definitions and utility routines for the ArduPilot libraries.
void set_gyro(uint8_t instance, const Vector3f &gyro)
void detect_backends(void)
virtual void delay_microseconds_boost(uint16_t us)
AP_Int8 _acc_body_aligned
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
static constexpr float radians(float deg)
static struct notify_flags_and_values_type flags
float accel_peak_hold_neg_x
virtual void accumulate()
void init(uint16_t sample_rate_hz)
BatchSampler batchsampler
struct AP_InertialSensor::PeakHoldState _peak_hold_state
void wait_for_sample(void)
AuxiliaryBus * get_auxiliary_bus(int16_t backend_id)
virtual void delay_microseconds(uint16_t us)=0
bool gyro_calibrated_ok_all() const
float _delta_angle_dt[INS_MAX_INSTANCES]
AP_Vector3f _gyro_offset[INS_MAX_INSTANCES]
bool get_new_trim(float &trim_roll, float &trim_pitch)
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
Vector3f _delta_velocity_acc[INS_MAX_INSTANCES]
uint8_t get_gyro_count(void) const
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a, enum Rotation rotation_g)
AP_InertialSensor & ins()
void calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt)
#define HAL_INS_LSM9DS0_EXT_G_NAME
uint32_t accel_peak_hold_neg_x_age
uint8_t _accel_over_sampling[INS_MAX_INSTANCES]
uint32_t _accel_clip_count[INS_MAX_INSTANCES]
bool _accel_healthy[INS_MAX_INSTANCES]
void panic(const char *errormsg,...) FMT_PRINTF(1
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
float get_delta_velocity_dt() const
#define HAL_INS_MPU6500_NAME
#define INS_MAX_INSTANCES
AP_Vector3f _accel_offset[INS_MAX_INSTANCES]
#define AP_INERTIAL_SENSOR_ACCEL_VIBE_FILT_HZ
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
static AP_InertialSensor * get_instance()
float get_delta_angle_dt() const
bool accel_calibrated_ok_all() const
Vector3f get_vibration_levels() const
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev)
Vector3f _accel[INS_MAX_INSTANCES]
NotchFilterVector3fParam _notch_filter
uint32_t _gyro_startup_error_count[INS_MAX_INSTANCES]
AccelCalibrator * _accel_calibrator
#define HAL_INS_LSM9DS0_G_NAME
bool get_gyro_health_all(void) const
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
#define AP_INERTIAL_SENSOR_ACCEL_CLIP_THRESH_MSS
AP_HAL::Scheduler * scheduler
bool get_fixed_mount_accel_cal_sample(uint8_t sample_num, Vector3f &ret) const
uint8_t get_accel_count(void) const
T apply(T sample, float dt)
uint32_t _last_sample_usec
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
#define HAL_INS_DEFAULT_ROTATION
static void sensor_config_error(const char *reason)