mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_InertialSensor: re-work for more flexible main loop rates
This commit is contained in:
parent
93ef881109
commit
17fc58f3cd
@ -430,7 +430,7 @@ AP_InertialSensor_Backend *AP_InertialSensor::_find_backend(int16_t backend_id,
|
|||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
AP_InertialSensor::init(Sample_rate sample_rate)
|
AP_InertialSensor::init(uint16_t sample_rate)
|
||||||
{
|
{
|
||||||
// remember the sample rate
|
// remember the sample rate
|
||||||
_sample_rate = sample_rate;
|
_sample_rate = sample_rate;
|
||||||
@ -453,21 +453,7 @@ AP_InertialSensor::init(Sample_rate sample_rate)
|
|||||||
_init_gyro();
|
_init_gyro();
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (sample_rate) {
|
_sample_period_usec = 1000*1000UL / _sample_rate;
|
||||||
case RATE_50HZ:
|
|
||||||
_sample_period_usec = 20000;
|
|
||||||
break;
|
|
||||||
case RATE_100HZ:
|
|
||||||
_sample_period_usec = 10000;
|
|
||||||
break;
|
|
||||||
case RATE_200HZ:
|
|
||||||
_sample_period_usec = 5000;
|
|
||||||
break;
|
|
||||||
case RATE_400HZ:
|
|
||||||
default:
|
|
||||||
_sample_period_usec = 2500;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
// establish the baseline time between samples
|
// establish the baseline time between samples
|
||||||
_delta_time = 0;
|
_delta_time = 0;
|
||||||
|
@ -49,14 +49,6 @@ public:
|
|||||||
AP_InertialSensor();
|
AP_InertialSensor();
|
||||||
static AP_InertialSensor *get_instance();
|
static AP_InertialSensor *get_instance();
|
||||||
|
|
||||||
// the rate that updates will be available to the application
|
|
||||||
enum Sample_rate {
|
|
||||||
RATE_50HZ = 50,
|
|
||||||
RATE_100HZ = 100,
|
|
||||||
RATE_200HZ = 200,
|
|
||||||
RATE_400HZ = 400
|
|
||||||
};
|
|
||||||
|
|
||||||
enum Gyro_Calibration_Timing {
|
enum Gyro_Calibration_Timing {
|
||||||
GYRO_CAL_NEVER = 0,
|
GYRO_CAL_NEVER = 0,
|
||||||
GYRO_CAL_STARTUP_ONLY = 1
|
GYRO_CAL_STARTUP_ONLY = 1
|
||||||
@ -70,7 +62,7 @@ public:
|
|||||||
///
|
///
|
||||||
/// @param style The initialisation startup style.
|
/// @param style The initialisation startup style.
|
||||||
///
|
///
|
||||||
void init(Sample_rate sample_rate);
|
void init(uint16_t sample_rate_hz);
|
||||||
|
|
||||||
/// Register a new gyro/accel driver, allocating an instance
|
/// Register a new gyro/accel driver, allocating an instance
|
||||||
/// number
|
/// number
|
||||||
@ -179,7 +171,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return the selected sample rate
|
// return the selected sample rate
|
||||||
Sample_rate get_sample_rate(void) const { return _sample_rate; }
|
uint16_t get_sample_rate(void) const { return _sample_rate; }
|
||||||
|
|
||||||
// return the main loop delta_t in seconds
|
// return the main loop delta_t in seconds
|
||||||
float get_loop_delta_t(void) const { return _loop_delta_t; }
|
float get_loop_delta_t(void) const { return _loop_delta_t; }
|
||||||
@ -275,7 +267,7 @@ private:
|
|||||||
uint8_t _backend_count;
|
uint8_t _backend_count;
|
||||||
|
|
||||||
// the selected sample rate
|
// the selected sample rate
|
||||||
Sample_rate _sample_rate;
|
uint16_t _sample_rate;
|
||||||
float _loop_delta_t;
|
float _loop_delta_t;
|
||||||
|
|
||||||
// Most recent accelerometer reading
|
// Most recent accelerometer reading
|
||||||
|
Loading…
Reference in New Issue
Block a user