mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: fixed compass for tailsitters in SITL
This commit is contained in:
parent
f06637d48e
commit
cbd6f4cc21
|
@ -202,3 +202,8 @@ bool AP_Compass_Backend::field_ok(const Vector3f &field)
|
|||
return ret;
|
||||
}
|
||||
|
||||
|
||||
enum Rotation AP_Compass_Backend::get_board_orientation(void) const
|
||||
{
|
||||
return _compass._board_orientation;
|
||||
}
|
||||
|
|
|
@ -106,6 +106,9 @@ protected:
|
|||
// set rotation of an instance
|
||||
void set_rotation(uint8_t instance, enum Rotation rotation);
|
||||
|
||||
// get board orientation (for SITL)
|
||||
enum Rotation get_board_orientation(void) const;
|
||||
|
||||
// access to frontend
|
||||
Compass &_compass;
|
||||
|
||||
|
|
|
@ -114,7 +114,9 @@ void AP_Compass_SITL::_timer()
|
|||
if (i == 0) {
|
||||
// rotate the first compass, allowing for testing of external compass rotation
|
||||
f.rotate_inverse((enum Rotation)_sitl->mag_orient.get());
|
||||
f.rotate(get_board_orientation());
|
||||
}
|
||||
|
||||
rotate_field(f, _compass_instance[i]);
|
||||
publish_raw_field(f, _compass_instance[i]);
|
||||
correct_field(f, _compass_instance[i]);
|
||||
|
|
Loading…
Reference in New Issue