AP_InertialSensor: Backend: remove function _publish_delta_angle()

Delta angle calculation is now unified, so there is no need for such a method.
That also avoids developers thinking they need that method being called
somewhere in their new drivers.
This commit is contained in:
Gustavo Jose de Sousa 2015-09-10 09:37:16 -03:00 committed by Andrew Tridgell
parent 7fef515555
commit 6feea5f64f
2 changed files with 0 additions and 9 deletions

View File

@ -37,13 +37,6 @@ void AP_InertialSensor_Backend::_rotate_and_correct_gyro(uint8_t instance, Vecto
gyro.rotate(_imu._board_orientation);
}
void AP_InertialSensor_Backend::_publish_delta_angle(uint8_t instance, const Vector3f &delta_angle)
{
// publish delta angle
_imu._delta_angle[instance] = delta_angle;
_imu._delta_angle_valid[instance] = true;
}
/*
rotate gyro vector and add the gyro offset
*/

View File

@ -80,8 +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_angle(uint8_t instance, const Vector3f &delta_angle);
// rotate gyro vector, offset and publish
void _publish_gyro(uint8_t instance, const Vector3f &gyro);