@ -11,21 +11,6 @@ AP_Compass_Backend::AP_Compass_Backend(Compass &compass) :
@@ -11,21 +11,6 @@ AP_Compass_Backend::AP_Compass_Backend(Compass &compass) :
_compass ( compass )
{ }
/*
* A compass measurement is expected to pass through the following functions :
* 1. rotate_field - this rotates the measurement in - place from sensor frame
* to body frame
* 2. publish_raw_field - this provides an uncorrected point - sample for
* calibration libraries
* 3. correct_field - this corrects the measurement in - place for hard iron ,
* soft iron , motor interference , and non - orthagonality errors
* 4. publish_unfiltered_field - this ( optionally ) provides a corrected
* point sample for fusion into the EKF
* 5. publish_filtered_field - legacy filtered magnetic field
*
* All those functions expect the mag field to be in milligauss .
*/
void AP_Compass_Backend : : rotate_field ( Vector3f & mag , uint8_t instance )
{
Compass : : mag_state & state = _compass . _state [ instance ] ;
@ -44,16 +29,10 @@ void AP_Compass_Backend::publish_raw_field(const Vector3f &mag, uint32_t time_us
@@ -44,16 +29,10 @@ void AP_Compass_Backend::publish_raw_field(const Vector3f &mag, uint32_t time_us
{
Compass : : mag_state & state = _compass . _state [ instance ] ;
state . last_update_ms = AP_HAL : : millis ( ) ;
// note that we do not set last_update_usec here as otherwise the
// EKF and DCM would end up consuming compass data at the full
// sensor rate. We want them to consume only the filtered fields
state . raw_field = mag ;
state . raw_meas_time_us = time_us ;
state . updated_raw_field = true ;
state . has_raw_field = true ;
state . last_update_ms = AP_HAL : : millis ( ) ;
_compass . _calibrator [ instance ] . new_sample ( mag ) ;
}
@ -92,16 +71,6 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
@@ -92,16 +71,6 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
mag = mat * mag ;
}
void AP_Compass_Backend : : publish_unfiltered_field ( const Vector3f & mag , uint32_t time_us , uint8_t instance )
{
Compass : : mag_state & state = _compass . _state [ instance ] ;
state . unfiltered_field = mag ;
state . raw_meas_time_us = time_us ;
state . updated_unfiltered_field = true ;
state . has_unfiltered_field = true ;
}
/*
copy latest data to the frontend from a backend
*/
@ -113,12 +82,6 @@ void AP_Compass_Backend::publish_filtered_field(const Vector3f &mag, uint8_t ins
@@ -113,12 +82,6 @@ void AP_Compass_Backend::publish_filtered_field(const Vector3f &mag, uint8_t ins
state . last_update_ms = AP_HAL : : millis ( ) ;
state . last_update_usec = AP_HAL : : micros ( ) ;
state . has_raw_field = state . updated_raw_field ;
state . updated_raw_field = false ;
state . has_unfiltered_field = state . updated_unfiltered_field ;
state . updated_unfiltered_field = false ;
}
/*