mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: added vector compass setHIL method
This commit is contained in:
parent
e7a1331b81
commit
bc2d17e76e
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue