mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Compass: add motor compensation to HIL library
This commit is contained in:
parent
6b2b69535f
commit
8093c98cd3
@ -18,6 +18,17 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
bool AP_Compass_HIL::read()
|
bool AP_Compass_HIL::read()
|
||||||
{
|
{
|
||||||
|
// get offsets
|
||||||
|
Vector3f ofs = _offset.get();
|
||||||
|
|
||||||
|
// get motor compensation
|
||||||
|
_motor_offset = _motor_compensation.get() * _throttle_pct;
|
||||||
|
|
||||||
|
// return last values provided by setHIL function
|
||||||
|
mag_x = _hil_mag.x + ofs.x + _motor_offset.x;
|
||||||
|
mag_y = _hil_mag.y + ofs.y + _motor_offset.y;
|
||||||
|
mag_z = _hil_mag.z + ofs.z + _motor_offset.z;
|
||||||
|
|
||||||
// values set by setHIL function
|
// values set by setHIL function
|
||||||
last_update = hal.scheduler->micros(); // record time of update
|
last_update = hal.scheduler->micros(); // record time of update
|
||||||
return true;
|
return true;
|
||||||
@ -27,10 +38,9 @@ bool AP_Compass_HIL::read()
|
|||||||
//
|
//
|
||||||
void AP_Compass_HIL::setHIL(float _mag_x, float _mag_y, float _mag_z)
|
void AP_Compass_HIL::setHIL(float _mag_x, float _mag_y, float _mag_z)
|
||||||
{
|
{
|
||||||
Vector3f ofs = _offset.get();
|
_hil_mag.x = _mag_x;
|
||||||
mag_x = _mag_x + ofs.x;
|
_hil_mag.y = _mag_y;
|
||||||
mag_y = _mag_y + ofs.y;
|
_hil_mag.z = _mag_z;
|
||||||
mag_z = _mag_z + ofs.z;
|
|
||||||
healthy = true;
|
healthy = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -13,6 +13,8 @@ public:
|
|||||||
bool read(void);
|
bool read(void);
|
||||||
void accumulate(void);
|
void accumulate(void);
|
||||||
void setHIL(float Mag_X, float Mag_Y, float Mag_Z);
|
void setHIL(float Mag_X, float Mag_Y, float Mag_Z);
|
||||||
|
private:
|
||||||
|
Vector3f _hil_mag;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user