mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: avoid logging unused IMU data
This commit is contained in:
parent
7d7031d3d7
commit
fabac94952
|
@ -29,15 +29,19 @@ void AP_DAL_InertialSensor::start_frame()
|
|||
log_RISI &RISI = _RISI[i];
|
||||
const log_RISI old_RISI = RISI;
|
||||
|
||||
// accel stuff
|
||||
// accel data
|
||||
RISI.use_accel = ins.use_accel(i);
|
||||
RISI.get_delta_velocity_ret = ins.get_delta_velocity(i, RISI.delta_velocity);
|
||||
RISI.delta_velocity_dt = ins.get_delta_velocity_dt(i);
|
||||
if (RISI.use_accel) {
|
||||
RISI.get_delta_velocity_ret = ins.get_delta_velocity(i, RISI.delta_velocity);
|
||||
RISI.delta_velocity_dt = ins.get_delta_velocity_dt(i);
|
||||
}
|
||||
|
||||
// gryo stuff
|
||||
// gryo data
|
||||
RISI.use_gyro = ins.use_gyro(i);
|
||||
RISI.delta_angle_dt = ins.get_delta_angle_dt(i);
|
||||
RISI.get_delta_angle_ret = ins.get_delta_angle(i, RISI.delta_angle);
|
||||
if (RISI.use_gyro) {
|
||||
RISI.delta_angle_dt = ins.get_delta_angle_dt(i);
|
||||
RISI.get_delta_angle_ret = ins.get_delta_angle(i, RISI.delta_angle);
|
||||
}
|
||||
|
||||
update_filtered(i);
|
||||
|
||||
|
|
Loading…
Reference in New Issue