AP_InertialSensor: added set of delta angle time for replay

This commit is contained in:
Andrew Tridgell 2016-04-26 15:50:46 +10:00
parent bcefb45e0a
commit be41d402b5
2 changed files with 3 additions and 2 deletions

View File

@ -1242,11 +1242,12 @@ void AP_InertialSensor::set_delta_velocity(uint8_t instance, float deltavt, cons
/*
set delta angle for next update
*/
void AP_InertialSensor::set_delta_angle(uint8_t instance, const Vector3f &deltaa)
void AP_InertialSensor::set_delta_angle(uint8_t instance, const Vector3f &deltaa, float deltaat)
{
if (instance < INS_MAX_INSTANCES) {
_delta_angle_valid[instance] = true;
_delta_angle[instance] = deltaa;
_delta_angle_dt[instance] = deltaat;
}
}

View File

@ -218,7 +218,7 @@ public:
void set_gyro(uint8_t instance, const Vector3f &gyro);
void set_delta_time(float delta_time);
void set_delta_velocity(uint8_t instance, float deltavt, const Vector3f &deltav);
void set_delta_angle(uint8_t instance, const Vector3f &deltaa);
void set_delta_angle(uint8_t instance, const Vector3f &deltaa, float deltaat);
AuxiliaryBus *get_auxiliary_bus(int16_t backend_id) { return get_auxiliary_bus(backend_id, 0); }
AuxiliaryBus *get_auxiliary_bus(int16_t backend_id, uint8_t instance);