APM:Libraries
AP_Compass_Backend.h
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  Compass driver backend class. Each supported compass sensor type
18  needs to have an object derived from this class.
19  */
20 #pragma once
21 
22 #include "AP_Compass.h"
23 
24 class Compass; // forward declaration
26 {
27 public:
29 
30  // we declare a virtual destructor so that drivers can
31  // override with a custom destructor if need be.
32  virtual ~AP_Compass_Backend(void) {}
33 
34  // read sensor data
35  virtual void read(void) = 0;
36 
37  // accumulate a reading from the magnetometer. Optional in
38  // backends
39  virtual void accumulate(void) {};
40 
41  // callback for UAVCAN messages
42  virtual void handle_mag_msg(Vector3f &mag) {};
43 
44  /*
45  device driver IDs. These are used to fill in the devtype field
46  of the device ID, which shows up as COMPASS*ID* parameters to
47  users. The values are chosen for compatibility with existing PX4
48  drivers.
49  If a change is made to a driver that would make existing
50  calibration values invalid then this number must be changed.
51  */
52  enum DevTypes {
66  };
67 
68 
69 protected:
70 
71  /*
72  * A compass measurement is expected to pass through the following functions:
73  * 1. rotate_field - this rotates the measurement in-place from sensor frame
74  * to body frame
75  * 2. publish_raw_field - this provides an uncorrected point-sample for
76  * calibration libraries
77  * 3. correct_field - this corrects the measurement in-place for hard iron,
78  * soft iron, motor interference, and non-orthagonality errors
79  * 4. publish_filtered_field - legacy filtered magnetic field
80  *
81  * All those functions expect the mag field to be in milligauss.
82  */
83 
84  void rotate_field(Vector3f &mag, uint8_t instance);
85  void publish_raw_field(const Vector3f &mag, uint8_t instance);
86  void correct_field(Vector3f &mag, uint8_t i);
87  void publish_filtered_field(const Vector3f &mag, uint8_t instance);
88  void set_last_update_usec(uint32_t last_update, uint8_t instance);
89 
90  // register a new compass instance with the frontend
91  uint8_t register_compass(void) const;
92 
93  // set dev_id for an instance
94  void set_dev_id(uint8_t instance, uint32_t dev_id);
95 
96  // set external state for an instance
97  void set_external(uint8_t instance, bool external);
98 
99  // tell if instance is an external compass
100  bool is_external(uint8_t instance);
101 
102  // set rotation of an instance
103  void set_rotation(uint8_t instance, enum Rotation rotation);
104 
105  // access to frontend
107 
108  // semaphore for access to shared frontend data
110 
111  // Check that the compass field is valid by using a mean filter on the vector length
112  bool field_ok(const Vector3f &field);
113 
114  uint32_t get_error_count() const { return _error_count; }
115 private:
116  void apply_corrections(Vector3f &mag, uint8_t i);
117 
118  // mean field length for range filter
120  // number of dropped samples. Not used for now, but can be usable to choose more reliable sensor
121  uint32_t _error_count;
122 };
void set_last_update_usec(uint32_t last_update, uint8_t instance)
void set_external(uint8_t instance, bool external)
uint32_t get_error_count() const
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)
bool field_ok(const Vector3f &field)
void set_dev_id(uint8_t instance, uint32_t dev_id)
Rotation
Definition: rotations.h:27
void apply_corrections(Vector3f &mag, uint8_t i)
virtual void handle_mag_msg(Vector3f &mag)
uint8_t register_compass(void) const
static Compass compass
Definition: AHRS_Test.cpp:20
AP_HAL::Semaphore * _sem
virtual void accumulate(void)
void set_rotation(uint8_t instance, enum Rotation rotation)
virtual ~AP_Compass_Backend(void)
virtual void read(void)=0
bool is_external(uint8_t instance)
void publish_raw_field(const Vector3f &mag, uint8_t instance)
AP_Compass_Backend(Compass &compass)