APM:Libraries
AP_Compass_HIL.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AP_Compass_HIL.cpp - HIL backend for AP_Compass
18  *
19  */
20 
21 
22 #include <AP_HAL/AP_HAL.h>
23 #include "AP_Compass_HIL.h"
24 
25 extern const AP_HAL::HAL& hal;
26 
27 // constructor
29  AP_Compass_Backend(compass)
30 {
31  memset(_compass_instance, 0, sizeof(_compass_instance));
33 }
34 
35 // detect the sensor
37 {
38  AP_Compass_HIL *sensor = new AP_Compass_HIL(compass);
39  if (sensor == nullptr) {
40  return nullptr;
41  }
42  if (!sensor->init()) {
43  delete sensor;
44  return nullptr;
45  }
46  return sensor;
47 }
48 
49 bool
51 {
52  // register two compass instances
53  for (uint8_t i=0; i<HIL_NUM_COMPASSES; i++) {
55  }
56  return true;
57 }
58 
60 {
61  for (uint8_t i=0; i < ARRAY_SIZE(_compass_instance); i++) {
62  if (_compass._hil.healthy[i]) {
63  uint8_t compass_instance = _compass_instance[i];
64  Vector3f field = _compass._hil.field[compass_instance];
65  rotate_field(field, compass_instance);
66  publish_raw_field(field, compass_instance);
67  correct_field(field, compass_instance);
68  uint32_t saved_last_update = _compass.last_update_usec(compass_instance);
69  publish_filtered_field(field, compass_instance);
70  set_last_update_usec(saved_last_update, compass_instance);
71  }
72  }
73 }
void set_last_update_usec(uint32_t last_update, uint8_t instance)
static AP_Compass_Backend * detect(Compass &compass)
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void rotate_field(Vector3f &mag, uint8_t instance)
void publish_filtered_field(const Vector3f &mag, uint8_t instance)
void correct_field(Vector3f &mag, uint8_t i)
void _setup_earth_field()
uint8_t register_compass(void) const
Vector3f field[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:302
bool healthy[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:301
static Compass compass
Definition: AHRS_Test.cpp:20
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
struct Compass::@17 _hil
uint8_t _compass_instance[HIL_NUM_COMPASSES]
uint32_t last_update_usec(void) const
Definition: AP_Compass.h:289
AP_Compass_HIL(Compass &compass)
void publish_raw_field(const Vector3f &mag, uint8_t instance)
#define HIL_NUM_COMPASSES
Definition: AP_Compass_HIL.h:5