AP_InertialSensor: Backend: remove function _publish_delta_velocity()

The delta velocity calculation is now unified, so there is no need for such a
method. That also avoids delevopers thinking they need that method being called
somewhere in their new drivers.
This commit is contained in:
Gustavo Jose de Sousa 2015-09-08 11:53:56 -03:00 committed by Andrew Tridgell
parent 75fdac648f
commit a3e2c82491
2 changed files with 0 additions and 9 deletions

View File

@ -53,14 +53,6 @@ void AP_InertialSensor_Backend::_publish_gyro(uint8_t instance, const Vector3f &
_imu._gyro_healthy[instance] = true;
}
void AP_InertialSensor_Backend::_publish_delta_velocity(uint8_t instance, const Vector3f &delta_velocity, float dt)
{
// publish delta velocity
_imu._delta_velocity[instance] = delta_velocity;
_imu._delta_velocity_dt[instance] = dt;
_imu._delta_velocity_valid[instance] = true;
}
/*
rotate accel vector, scale and add the accel offset
*/

View File

@ -80,7 +80,6 @@ protected:
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel);
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro);
void _publish_delta_velocity(uint8_t instance, const Vector3f &delta_velocity, float dt);
void _publish_delta_angle(uint8_t instance, const Vector3f &delta_angle);
// rotate gyro vector, offset and publish