AP_Compass: added vector compass setHIL method

This commit is contained in:
Andrew Tridgell 2013-12-29 22:55:20 +11:00
parent e7a1331b81
commit bc2d17e76e
2 changed files with 12 additions and 0 deletions

View File

@ -106,6 +106,16 @@ void AP_Compass_HIL::setHIL(float roll, float pitch, float yaw)
_healthy[0] = true;
}
// Update raw magnetometer values from HIL mag vector
//
void AP_Compass_HIL::setHIL(const Vector3i &mag)
{
_hil_mag.x = mag.x;
_hil_mag.y = mag.y;
_hil_mag.z = mag.z;
_healthy[0] = true;
}
void AP_Compass_HIL::accumulate(void)
{
// nothing to do

View File

@ -11,6 +11,8 @@ public:
bool read(void);
void accumulate(void);
void setHIL(float roll, float pitch, float yaw);
void setHIL(const Vector3i &mag);
private:
Vector3f _hil_mag;
Vector3f _Bearth;