mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_InertialSensor: use raw sample rate terminology
In order to avoid confusion between sample rate from sensor and sample rate from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to the former. The changes in the code were basically done with the following commands: git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g" git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g" git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g" git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g" git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g" git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g" And also with minor changes on indentation and comments.
This commit is contained in:
parent
6feea5f64f
commit
25a499a41f
@ -338,8 +338,8 @@ AP_InertialSensor::AP_InertialSensor() :
|
||||
|
||||
_accel_max_abs_offsets[i] = 3.5f;
|
||||
|
||||
_accel_sample_rates[i] = 0;
|
||||
_gyro_sample_rates[i] = 0;
|
||||
_accel_raw_sample_rates[i] = 0;
|
||||
_gyro_raw_sample_rates[i] = 0;
|
||||
|
||||
_delta_velocity_acc[i].zero();
|
||||
_delta_velocity_acc_dt[i] = 0;
|
||||
|
@ -301,8 +301,8 @@ private:
|
||||
float _accel_max_abs_offsets[INS_MAX_INSTANCES];
|
||||
|
||||
// accelerometer and gyro raw sample rate in units of Hz
|
||||
uint32_t _accel_sample_rates[INS_MAX_INSTANCES];
|
||||
uint32_t _gyro_sample_rates[INS_MAX_INSTANCES];
|
||||
uint32_t _accel_raw_sample_rates[INS_MAX_INSTANCES];
|
||||
uint32_t _gyro_raw_sample_rates[INS_MAX_INSTANCES];
|
||||
|
||||
// temperatures for an instance if available
|
||||
float _temperature[INS_MAX_INSTANCES];
|
||||
|
@ -45,7 +45,7 @@ void AP_InertialSensor_Backend::_publish_gyro(uint8_t instance, const Vector3f &
|
||||
_imu._gyro[instance] = gyro;
|
||||
_imu._gyro_healthy[instance] = true;
|
||||
|
||||
if (_imu._gyro_sample_rates[instance] <= 0) {
|
||||
if (_imu._gyro_raw_sample_rates[instance] <= 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -59,11 +59,11 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance,
|
||||
{
|
||||
float dt;
|
||||
|
||||
if (_imu._gyro_sample_rates[instance] <= 0) {
|
||||
if (_imu._gyro_raw_sample_rates[instance] <= 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
dt = 1.0f / _imu._gyro_sample_rates[instance];
|
||||
dt = 1.0f / _imu._gyro_raw_sample_rates[instance];
|
||||
|
||||
// compute delta angle
|
||||
Vector3f delta_angle = (gyro + _imu._last_raw_gyro[instance]) * 0.5f * dt;
|
||||
@ -97,7 +97,7 @@ void AP_InertialSensor_Backend::_publish_accel(uint8_t instance, const Vector3f
|
||||
_imu._accel[instance] = accel;
|
||||
_imu._accel_healthy[instance] = true;
|
||||
|
||||
if (_imu._accel_sample_rates[instance] <= 0) {
|
||||
if (_imu._accel_raw_sample_rates[instance] <= 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -112,11 +112,11 @@ void AP_InertialSensor_Backend::_notify_new_accel_raw_sample(uint8_t instance,
|
||||
{
|
||||
float dt;
|
||||
|
||||
if (_imu._accel_sample_rates[instance] <= 0) {
|
||||
if (_imu._accel_raw_sample_rates[instance] <= 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
dt = 1.0f / _imu._accel_sample_rates[instance];
|
||||
dt = 1.0f / _imu._accel_raw_sample_rates[instance];
|
||||
|
||||
#if INS_VIBRATION_CHECK
|
||||
_imu.calc_vibration_and_clipping(instance, accel, dt);
|
||||
@ -133,10 +133,10 @@ void AP_InertialSensor_Backend::_set_accel_max_abs_offset(uint8_t instance,
|
||||
_imu._accel_max_abs_offsets[instance] = max_offset;
|
||||
}
|
||||
|
||||
void AP_InertialSensor_Backend::_set_accel_sample_rate(uint8_t instance,
|
||||
uint32_t rate)
|
||||
void AP_InertialSensor_Backend::_set_accel_raw_sample_rate(uint8_t instance,
|
||||
uint32_t rate)
|
||||
{
|
||||
_imu._accel_sample_rates[instance] = rate;
|
||||
_imu._accel_raw_sample_rates[instance] = rate;
|
||||
}
|
||||
|
||||
// set accelerometer error_count
|
||||
@ -145,8 +145,8 @@ void AP_InertialSensor_Backend::_set_accel_error_count(uint8_t instance, uint32_
|
||||
_imu._accel_error_count[instance] = error_count;
|
||||
}
|
||||
|
||||
void AP_InertialSensor_Backend::_set_gyro_sample_rate(uint8_t instance,
|
||||
uint32_t rate)
|
||||
void AP_InertialSensor_Backend::_set_gyro_raw_sample_rate(uint8_t instance,
|
||||
uint32_t rate)
|
||||
{
|
||||
_imu._gyro_raw_sample_rates[instance] = rate;
|
||||
}
|
||||
|
@ -101,16 +101,16 @@ protected:
|
||||
// set accelerometer max absolute offset for calibration
|
||||
void _set_accel_max_abs_offset(uint8_t instance, float offset);
|
||||
|
||||
// set accelerometer sample rate
|
||||
void _set_accel_sample_rate(uint8_t instance, uint32_t rate);
|
||||
uint32_t _accel_sample_rate(uint8_t instance) const {
|
||||
return _imu._accel_sample_rates[instance];
|
||||
// set accelerometer raw sample rate
|
||||
void _set_accel_raw_sample_rate(uint8_t instance, uint32_t rate);
|
||||
uint32_t _accel_raw_sample_rate(uint8_t instance) const {
|
||||
return _imu._accel_raw_sample_rates[instance];
|
||||
}
|
||||
|
||||
// set gyroscope sample rate
|
||||
void _set_gyro_sample_rate(uint8_t instance, uint32_t rate);
|
||||
uint32_t _gyro_sample_rate(uint8_t instance) const {
|
||||
return _imu._gyro_sample_rates[instance];
|
||||
// set gyroscope raw sample rate
|
||||
void _set_gyro_raw_sample_rate(uint8_t instance, uint32_t rate);
|
||||
uint32_t _gyro_raw_sample_rate(uint8_t instance) const {
|
||||
return _imu._gyro_raw_sample_rates[instance];
|
||||
}
|
||||
|
||||
// publish a temperature value
|
||||
|
@ -593,7 +593,7 @@ void AP_InertialSensor_MPU6000::start()
|
||||
_gyro_instance = _imu.register_gyro();
|
||||
_accel_instance = _imu.register_accel();
|
||||
|
||||
_set_accel_sample_rate(_accel_instance, 1000);
|
||||
_set_accel_raw_sample_rate(_accel_instance, 1000);
|
||||
|
||||
hal.scheduler->resume_timer_procs();
|
||||
|
||||
|
@ -315,7 +315,7 @@ bool AP_InertialSensor_MPU9250::_init_sensor(AP_HAL::SPIDeviceDriver *spi)
|
||||
// start the timer process to read samples
|
||||
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_MPU9250::_poll_data, void));
|
||||
|
||||
_set_accel_sample_rate(_accel_instance, DEFAULT_SAMPLE_RATE);
|
||||
_set_accel_raw_sample_rate(_accel_instance, DEFAULT_SAMPLE_RATE);
|
||||
|
||||
#if MPU9250_DEBUG
|
||||
_dump_registers(_spi);
|
||||
|
@ -161,7 +161,7 @@ bool AP_InertialSensor_PX4::_init_sensor(void)
|
||||
if (samplerate < 100 || samplerate > 10000) {
|
||||
hal.scheduler->panic("Invalid accel sample rate");
|
||||
}
|
||||
_set_accel_sample_rate(_accel_instance[i], (uint32_t) samplerate);
|
||||
_set_accel_raw_sample_rate(_accel_instance[i], (uint32_t) samplerate);
|
||||
_accel_sample_time[i] = 1.0f / samplerate;
|
||||
}
|
||||
|
||||
@ -186,7 +186,7 @@ bool AP_InertialSensor_PX4::_init_sensor(void)
|
||||
void AP_InertialSensor_PX4::_set_accel_filter_frequency(uint8_t filter_hz)
|
||||
{
|
||||
for (uint8_t i=0; i<_num_accel_instances; i++) {
|
||||
float samplerate = _accel_sample_rate(_accel_instance[i]);
|
||||
float samplerate = _accel_raw_sample_rate(_accel_instance[i]);
|
||||
_accel_filter[i].set_cutoff_frequency(samplerate, filter_hz);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user