Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_HMC5843.h
9693 views
1
#pragma once
2
3
#include "AP_Compass_config.h"
4
5
#if AP_COMPASS_HMC5843_ENABLED
6
7
#ifndef HAL_COMPASS_HMC5843_I2C_ADDR
8
#define HAL_COMPASS_HMC5843_I2C_ADDR 0x1E
9
#endif
10
11
#include <AP_Common/AP_Common.h>
12
#include <AP_HAL/AP_HAL.h>
13
#include <AP_HAL/Device.h>
14
15
#include "AP_Compass_Backend.h"
16
#include <AP_InertialSensor/AP_InertialSensor_config.h>
17
18
class AuxiliaryBus;
19
class AuxiliaryBusSlave;
20
class AP_InertialSensor;
21
class AP_HMC5843_BusDriver;
22
23
class AP_Compass_HMC5843 : public AP_Compass_Backend
24
{
25
public:
26
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
27
bool force_external,
28
enum Rotation rotation);
29
30
#if AP_INERTIALSENSOR_ENABLED
31
static AP_Compass_Backend *probe_mpu6000(enum Rotation rotation);
32
#endif
33
34
static constexpr const char *name = "HMC5843";
35
36
virtual ~AP_Compass_HMC5843();
37
38
void read() override;
39
40
private:
41
AP_Compass_HMC5843(AP_HMC5843_BusDriver *bus,
42
bool force_external, enum Rotation rotation);
43
44
bool init();
45
bool _check_whoami();
46
bool _calibrate();
47
bool _setup_sampling_mode();
48
49
void _timer();
50
51
/* Read a single sample */
52
bool _read_sample();
53
54
// ask for a new sample
55
void _take_sample();
56
57
AP_HMC5843_BusDriver *_bus;
58
59
Vector3f _scaling;
60
float _gain_scale;
61
62
int16_t _mag_x;
63
int16_t _mag_y;
64
int16_t _mag_z;
65
66
enum Rotation _rotation;
67
68
bool _initialised:1;
69
bool _force_external:1;
70
};
71
72
class AP_HMC5843_BusDriver
73
{
74
public:
75
virtual ~AP_HMC5843_BusDriver() { }
76
77
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;
78
virtual bool register_read(uint8_t reg, uint8_t *val) = 0;
79
virtual bool register_write(uint8_t reg, uint8_t val) = 0;
80
81
virtual AP_HAL::Semaphore *get_semaphore() = 0;
82
83
virtual bool configure() { return true; }
84
virtual bool start_measurements() { return true; }
85
86
virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;
87
88
// set device type within a device class
89
virtual void set_device_type(uint8_t devtype) = 0;
90
91
// return 24 bit bus identifier
92
virtual uint32_t get_bus_id(void) const = 0;
93
94
virtual void set_retries(uint8_t retries) {}
95
};
96
97
class AP_HMC5843_BusDriver_HALDevice : public AP_HMC5843_BusDriver
98
{
99
public:
100
AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);
101
102
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
103
bool register_read(uint8_t reg, uint8_t *val) override;
104
bool register_write(uint8_t reg, uint8_t val) override;
105
106
AP_HAL::Semaphore *get_semaphore() override;
107
108
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
109
110
// set device type within a device class
111
void set_device_type(uint8_t devtype) override {
112
_dev->set_device_type(devtype);
113
}
114
115
// return 24 bit bus identifier
116
uint32_t get_bus_id(void) const override {
117
return _dev->get_bus_id();
118
}
119
120
void set_retries(uint8_t retries) override {
121
return _dev->set_retries(retries);
122
}
123
124
private:
125
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
126
};
127
128
#if AP_INERTIALSENSOR_ENABLED
129
class AP_HMC5843_BusDriver_Auxiliary : public AP_HMC5843_BusDriver
130
{
131
public:
132
AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
133
uint8_t addr);
134
virtual ~AP_HMC5843_BusDriver_Auxiliary();
135
136
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
137
bool register_read(uint8_t reg, uint8_t *val) override;
138
bool register_write(uint8_t reg, uint8_t val) override;
139
140
AP_HAL::Semaphore *get_semaphore() override;
141
142
bool configure() override;
143
bool start_measurements() override;
144
145
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
146
147
// set device type within a device class
148
void set_device_type(uint8_t devtype) override;
149
150
// return 24 bit bus identifier
151
uint32_t get_bus_id(void) const override;
152
153
private:
154
AuxiliaryBus *_bus;
155
AuxiliaryBusSlave *_slave;
156
bool _started;
157
};
158
#endif // AP_INERTIALSENSOR_ENABLED
159
160
#endif // AP_COMPASS_HMC5843_ENABLED
161
162