mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: remove separate calls to get delta-times for vel and ang
This commit is contained in:
parent
ea1884f491
commit
a0fcd74b52
|
@ -32,15 +32,13 @@ void AP_DAL_InertialSensor::start_frame()
|
||||||
// accel data
|
// accel data
|
||||||
RISI.use_accel = ins.use_accel(i);
|
RISI.use_accel = ins.use_accel(i);
|
||||||
if (RISI.use_accel) {
|
if (RISI.use_accel) {
|
||||||
RISI.get_delta_velocity_ret = ins.get_delta_velocity(i, RISI.delta_velocity);
|
RISI.get_delta_velocity_ret = ins.get_delta_velocity(i, RISI.delta_velocity, RISI.delta_velocity_dt);
|
||||||
RISI.delta_velocity_dt = ins.get_delta_velocity_dt(i);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// gryo data
|
// gryo data
|
||||||
RISI.use_gyro = ins.use_gyro(i);
|
RISI.use_gyro = ins.use_gyro(i);
|
||||||
if (RISI.use_gyro) {
|
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, RISI.delta_angle_dt);
|
||||||
RISI.get_delta_angle_ret = ins.get_delta_angle(i, RISI.delta_angle);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
update_filtered(i);
|
update_filtered(i);
|
||||||
|
|
|
@ -24,13 +24,11 @@ public:
|
||||||
|
|
||||||
bool use_accel(uint8_t instance) const { return _RISI[instance].use_accel; }
|
bool use_accel(uint8_t instance) const { return _RISI[instance].use_accel; }
|
||||||
const Vector3f &get_accel(uint8_t i) const { return accel_filtered[i]; }
|
const Vector3f &get_accel(uint8_t i) const { return accel_filtered[i]; }
|
||||||
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const {
|
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity, float &delta_velocity_dt) const {
|
||||||
delta_velocity = _RISI[i].delta_velocity;
|
delta_velocity = _RISI[i].delta_velocity;
|
||||||
|
delta_velocity_dt = _RISI[i].delta_velocity_dt;
|
||||||
return _RISI[i].get_delta_velocity_ret;
|
return _RISI[i].get_delta_velocity_ret;
|
||||||
}
|
}
|
||||||
float get_delta_velocity_dt(uint8_t i) const {
|
|
||||||
return _RISI[i].delta_velocity_dt;
|
|
||||||
}
|
|
||||||
|
|
||||||
// gyro stuff
|
// gyro stuff
|
||||||
uint8_t get_gyro_count(void) const { return _RISH.gyro_count; }
|
uint8_t get_gyro_count(void) const { return _RISH.gyro_count; }
|
||||||
|
@ -39,11 +37,11 @@ public:
|
||||||
bool use_gyro(uint8_t instance) const { return _RISI[instance].use_gyro; }
|
bool use_gyro(uint8_t instance) const { return _RISI[instance].use_gyro; }
|
||||||
const Vector3f &get_gyro(uint8_t i) const { return gyro_filtered[i]; }
|
const Vector3f &get_gyro(uint8_t i) const { return gyro_filtered[i]; }
|
||||||
const Vector3f &get_gyro() const { return get_gyro(_primary_gyro); }
|
const Vector3f &get_gyro() const { return get_gyro(_primary_gyro); }
|
||||||
bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const {
|
bool get_delta_angle(uint8_t i, Vector3f &delta_angle, float &delta_angle_dt) const {
|
||||||
delta_angle = _RISI[i].delta_angle;
|
delta_angle = _RISI[i].delta_angle;
|
||||||
|
delta_angle_dt = _RISI[i].delta_angle_dt;
|
||||||
return _RISI[i].get_delta_angle_ret;
|
return _RISI[i].get_delta_angle_ret;
|
||||||
}
|
}
|
||||||
float get_delta_angle_dt(uint8_t i) const { return _RISI[i].delta_angle_dt; }
|
|
||||||
|
|
||||||
// return the main loop delta_t in seconds
|
// return the main loop delta_t in seconds
|
||||||
float get_loop_delta_t(void) const { return _RISH.loop_delta_t; }
|
float get_loop_delta_t(void) const { return _RISH.loop_delta_t; }
|
||||||
|
|
Loading…
Reference in New Issue