mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Compass_PX4: use instance specific orient and external
This commit is contained in:
parent
023b6afe8b
commit
85e82a0399
@ -69,8 +69,8 @@ bool AP_Compass_PX4::init(void)
|
||||
}
|
||||
|
||||
// remember if the compass is external
|
||||
_is_external[i] = (ioctl(_mag_fd[i], MAGIOCGEXTERNAL, 0) > 0);
|
||||
if (_is_external[i]) {
|
||||
_external[i] = (ioctl(_mag_fd[i], MAGIOCGEXTERNAL, 0) > 0);
|
||||
if (_external[i]) {
|
||||
hal.console->printf("Using external compass[%u]\n", (unsigned)i);
|
||||
}
|
||||
_count[0] = 0;
|
||||
@ -108,12 +108,9 @@ bool AP_Compass_PX4::read(void)
|
||||
// a noop on most boards
|
||||
_sum[i].rotate(MAG_BOARD_ORIENTATION);
|
||||
|
||||
// override any user setting of COMPASS_EXTERNAL
|
||||
_external.set(_is_external[0]);
|
||||
|
||||
if (_is_external[i]) {
|
||||
if (_external[i]) {
|
||||
// add user selectable orientation
|
||||
_sum[i].rotate((enum Rotation)_orientation.get());
|
||||
_sum[i].rotate((enum Rotation)_orientation[i].get());
|
||||
} else {
|
||||
// add in board orientation from AHRS
|
||||
_sum[i].rotate(_board_orientation);
|
||||
|
@ -28,7 +28,6 @@ private:
|
||||
Vector3f _sum[COMPASS_MAX_INSTANCES];
|
||||
uint32_t _count[COMPASS_MAX_INSTANCES];
|
||||
uint64_t _last_timestamp[COMPASS_MAX_INSTANCES];
|
||||
bool _is_external[COMPASS_MAX_INSTANCES];
|
||||
};
|
||||
|
||||
#endif // AP_Compass_PX4_H
|
||||
|
Loading…
Reference in New Issue
Block a user