Skip to content

Commit ed85540

Browse files
AP_InertialSensor: prearm check to validate backend read rates against scheduler loop rate
1 parent f9e319d commit ed85540

File tree

6 files changed

+43
-0
lines changed

6 files changed

+43
-0
lines changed

libraries/AP_InertialSensor/AP_InertialSensor.cpp

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include "AP_InertialSensor_Invensensev3.h"
4040
#include "AP_InertialSensor_NONE.h"
4141
#include "AP_InertialSensor_SCHA63T.h"
42+
#include <AP_Scheduler/AP_Scheduler.h>
4243

4344
/* Define INS_TIMING_DEBUG to track down scheduling issues with the main loop.
4445
* Output is on the debug console. */
@@ -1492,6 +1493,24 @@ bool AP_InertialSensor::gyro_calibrated_ok_all() const
14921493
return (get_gyro_count() > 0);
14931494
}
14941495

1496+
// Prearm check to verify that we have sane sched loop rates set based on Gyro backend rates
1497+
bool AP_InertialSensor::pre_arm_check_gyro_backend_rate_hz(char* fail_msg, uint16_t fail_msg_len) const
1498+
{
1499+
#if AP_SCHEDULER_ENABLED
1500+
for (uint8_t i=0; i<get_gyro_count(); i++) {
1501+
if (!_use(i) || _backends[i] == nullptr) {
1502+
continue;
1503+
}
1504+
if (_backends[i]->get_gyro_backend_rate_hz() < (2*_loop_rate)) {
1505+
hal.util->snprintf(fail_msg, fail_msg_len, "Gyro %d backend rate %dHz < sched loop rate %dHz",
1506+
i, _backends[i]->get_gyro_backend_rate_hz(), _loop_rate);
1507+
return false;
1508+
}
1509+
}
1510+
#endif
1511+
return true;
1512+
}
1513+
14951514
// return true if gyro instance should be used (must be healthy and have it's use parameter set to 1)
14961515
bool AP_InertialSensor::use_gyro(uint8_t instance) const
14971516
{

libraries/AP_InertialSensor/AP_InertialSensor.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -156,6 +156,9 @@ class AP_InertialSensor : AP_AccelCal_Client
156156
uint16_t get_gyro_rate_hz(uint8_t instance) const { return uint16_t(_gyro_raw_sample_rates[instance] * _gyro_over_sampling[instance]); }
157157
uint16_t get_accel_rate_hz(uint8_t instance) const { return uint16_t(_accel_raw_sample_rates[instance] * _accel_over_sampling[instance]); }
158158

159+
// validate backend sample rates
160+
bool pre_arm_check_gyro_backend_rate_hz(char* fail_msg, uint16_t fail_msg_len) const;
161+
159162
// FFT support access
160163
#if HAL_GYROFFT_ENABLED
161164
const Vector3f& get_gyro_for_fft(void) const { return _gyro_for_fft[_first_usable_gyro]; }

libraries/AP_InertialSensor/AP_InertialSensor_Backend.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,12 @@ class AP_InertialSensor_Backend
9191
bool has_been_killed(uint8_t instance) const { return false; }
9292
#endif
9393

94+
// get the backend update rate for the gyro in Hz
95+
// if the backend polling rate is the same as the sample rate or higher, return raw sample rate
96+
// override and return the backend rate in Hz if it is lower than the sample rate
97+
virtual uint16_t get_gyro_backend_rate_hz() const {
98+
return _gyro_raw_sample_rate(gyro_instance);
99+
}
94100

95101
/*
96102
device driver IDs. These are used to fill in the devtype field

libraries/AP_InertialSensor/AP_InertialSensor_Invensense.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,11 @@ class AP_InertialSensor_Invensense : public AP_InertialSensor_Backend
5858
// get a startup banner to output to the GCS
5959
bool get_output_banner(char* banner, uint8_t banner_len) override;
6060

61+
// get the gyro backend rate in Hz at which the FIFO is being read
62+
uint16_t get_gyro_backend_rate_hz() const override {
63+
return _gyro_backend_rate_hz;
64+
}
65+
6166
enum Invensense_Type {
6267
Invensense_MPU6000=0,
6368
Invensense_MPU6500,

libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,11 @@ class AP_InertialSensor_Invensensev2 : public AP_InertialSensor_Backend
5555
// get a startup banner to output to the GCS
5656
bool get_output_banner(char* banner, uint8_t banner_len) override;
5757

58+
// get the gyro backend rate in Hz at which the FIFO is being read
59+
uint16_t get_gyro_backend_rate_hz() const override {
60+
return _gyro_backend_rate_hz;
61+
}
62+
5863
enum Invensensev2_Type {
5964
Invensensev2_ICM20948 = 0,
6065
Invensensev2_ICM20648,

libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,11 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend
7575
bool accumulate_samples(const struct FIFOData *data, uint8_t n_samples);
7676
bool accumulate_highres_samples(const struct FIFODataHighRes *data, uint8_t n_samples);
7777

78+
// get the gyro backend rate in Hz at which the FIFO is being read
79+
uint16_t get_gyro_backend_rate_hz() const override {
80+
return backend_rate_hz;
81+
}
82+
7883
// reset FIFO configure1 register
7984
uint8_t fifo_config1;
8085

0 commit comments

Comments
 (0)