AP_Compass: Separate common code into backend

_copy_to_frontend function takes care of abstracting
this code from the driver. For now the function takes
care of the offset and rotation that is common.
This commit is contained in:
Víctor Mayoral Vilches 2015-01-19 17:58:26 +01:00 committed by Andrew Tridgell
parent d3b76cd8d3
commit 13f0aa5ecd
5 changed files with 32 additions and 28 deletions

View File

@ -508,19 +508,7 @@ bool AP_Compass_AK8963::read()
_mag_x_accum = _mag_y_accum = _mag_z_accum = 0;
_accum_count = 0;
// apply default board orientation for this compass type. This is
// a noop on most boards
_compass._field[_compass_instance].rotate(MAG_BOARD_ORIENTATION);
// add user selectable orientation
_compass._field[_compass_instance].rotate((enum Rotation)_compass._orientation[_compass_instance].get());
if (!_compass._external[_compass_instance]) {
// and add in AHRS_ORIENTATION setting if not an external compass
_compass._field[_compass_instance].rotate(_compass._board_orientation);
}
_compass.apply_corrections(_compass._field[_compass_instance],_compass_instance);
_copy_to_frontend(_compass_instance);
#if 0

View File

@ -7,4 +7,24 @@
AP_Compass_Backend::AP_Compass_Backend(Compass &compass) :
_compass(compass),
product_id(AP_PRODUCT_ID_NONE)
{}
{}
/*
copy latest data to the frontend from a backend
*/
void AP_Compass_Backend::_copy_to_frontend(uint8_t instance) {
// apply default board orientation for this compass type. This is
// a noop on most boards
_compass._field[instance].rotate(MAG_BOARD_ORIENTATION);
// add user selectable orientation
_compass._field[instance].rotate((enum Rotation)_compass._orientation[instance].get());
if (!_compass._external[instance]) {
// and add in AHRS_ORIENTATION setting if not an external compass
_compass._field[instance].rotate(_compass.get_board_orientation());
}
_compass.apply_corrections(_compass._field[instance],instance);
}

View File

@ -49,6 +49,7 @@ protected:
virtual bool re_initialise(void) = 0;
Compass &_compass; ///< access to frontend
void _copy_to_frontend(uint8_t instance);
};
#endif // __AP_COMPASS_BACKEND_H__

View File

@ -387,19 +387,7 @@ bool AP_Compass_HMC5843::read()
_compass._field[_compass_instance].rotate(ROTATION_YAW_90);
}
// apply default board orientation for this compass type. This is
// a noop on most boards
_compass._field[_compass_instance].rotate(MAG_BOARD_ORIENTATION);
// add user selectable orientation
_compass._field[_compass_instance].rotate((enum Rotation)_compass.get_orientation(_compass_instance).get());
if (!_compass._external[_compass_instance]) {
// and add in AHRS_ORIENTATION setting if not an external compass
_compass._field[_compass_instance].rotate(_compass.get_board_orientation());
}
_compass.apply_corrections(_compass._field[_compass_instance], _compass_instance);
_copy_to_frontend(_compass_instance);
_compass._healthy[_compass_instance] = true;
return true;

View File

@ -66,6 +66,12 @@ extern const AP_HAL::HAL& hal;
class Compass
{
friend class AP_Compass_Backend;
friend class AP_Compass_HIL;
friend class AP_Compass_VRBRAIN;
friend class AP_Compass_PX4;
friend class AP_Compass_AK8963;
friend class AP_Compass_HMC5843;
public:
uint32_t last_update; ///< micros() time of last update
int16_t product_id; /// product id
@ -291,7 +297,6 @@ public:
// int16_t product_id(void) const { return product_id; }
AP_Int8 _external[COMPASS_MAX_INSTANCES]; ///<compass is external
bool _healthy[COMPASS_MAX_INSTANCES];
Vector3f _field[COMPASS_MAX_INSTANCES]; ///< magnetic field strength
// board orientation from AHRS
enum Rotation _board_orientation;
AP_Int8 _orientation[COMPASS_MAX_INSTANCES];
@ -331,6 +336,8 @@ protected:
Vector3f _Bearth;
float _last_declination;
private:
Vector3f _field[COMPASS_MAX_INSTANCES]; ///< magnetic field strength
};