123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_Compass_HIL.h"
- extern const AP_HAL::HAL& hal;
- AP_Compass_HIL::AP_Compass_HIL()
- {
- memset(_compass_instance, 0, sizeof(_compass_instance));
- _compass._setup_earth_field();
- }
- AP_Compass_Backend *AP_Compass_HIL::detect()
- {
- AP_Compass_HIL *sensor = new AP_Compass_HIL();
- if (sensor == nullptr) {
- return nullptr;
- }
- if (!sensor->init()) {
- delete sensor;
- return nullptr;
- }
- return sensor;
- }
- bool
- AP_Compass_HIL::init(void)
- {
-
- for (uint8_t i=0; i<HIL_NUM_COMPASSES; i++) {
- _compass_instance[i] = register_compass();
- }
- return true;
- }
- void AP_Compass_HIL::read()
- {
- for (uint8_t i=0; i < ARRAY_SIZE(_compass_instance); i++) {
- if (_compass._hil.healthy[i]) {
- uint8_t compass_instance = _compass_instance[i];
- Vector3f field = _compass._hil.field[compass_instance];
- rotate_field(field, compass_instance);
- publish_raw_field(field, compass_instance);
- correct_field(field, compass_instance);
- uint32_t saved_last_update = _compass.last_update_usec(compass_instance);
- publish_filtered_field(field, compass_instance);
- set_last_update_usec(saved_last_update, compass_instance);
- }
- }
- }
|