CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Compass/AP_Compass_HMC5843.h
Views: 1798
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
uint8_t _compass_instance;
67
68
enum Rotation _rotation;
69
70
bool _initialised:1;
71
bool _force_external:1;
72
};
73
74
class AP_HMC5843_BusDriver
75
{
76
public:
77
virtual ~AP_HMC5843_BusDriver() { }
78
79
virtual bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) = 0;
80
virtual bool register_read(uint8_t reg, uint8_t *val) = 0;
81
virtual bool register_write(uint8_t reg, uint8_t val) = 0;
82
83
virtual AP_HAL::Semaphore *get_semaphore() = 0;
84
85
virtual bool configure() { return true; }
86
virtual bool start_measurements() { return true; }
87
88
virtual AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t, AP_HAL::Device::PeriodicCb) = 0;
89
90
// set device type within a device class
91
virtual void set_device_type(uint8_t devtype) = 0;
92
93
// return 24 bit bus identifier
94
virtual uint32_t get_bus_id(void) const = 0;
95
96
virtual void set_retries(uint8_t retries) {}
97
};
98
99
class AP_HMC5843_BusDriver_HALDevice : public AP_HMC5843_BusDriver
100
{
101
public:
102
AP_HMC5843_BusDriver_HALDevice(AP_HAL::OwnPtr<AP_HAL::Device> dev);
103
104
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
105
bool register_read(uint8_t reg, uint8_t *val) override;
106
bool register_write(uint8_t reg, uint8_t val) override;
107
108
AP_HAL::Semaphore *get_semaphore() override;
109
110
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
111
112
// set device type within a device class
113
void set_device_type(uint8_t devtype) override {
114
_dev->set_device_type(devtype);
115
}
116
117
// return 24 bit bus identifier
118
uint32_t get_bus_id(void) const override {
119
return _dev->get_bus_id();
120
}
121
122
void set_retries(uint8_t retries) override {
123
return _dev->set_retries(retries);
124
}
125
126
private:
127
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
128
};
129
130
#if AP_INERTIALSENSOR_ENABLED
131
class AP_HMC5843_BusDriver_Auxiliary : public AP_HMC5843_BusDriver
132
{
133
public:
134
AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id,
135
uint8_t addr);
136
virtual ~AP_HMC5843_BusDriver_Auxiliary();
137
138
bool block_read(uint8_t reg, uint8_t *buf, uint32_t size) override;
139
bool register_read(uint8_t reg, uint8_t *val) override;
140
bool register_write(uint8_t reg, uint8_t val) override;
141
142
AP_HAL::Semaphore *get_semaphore() override;
143
144
bool configure() override;
145
bool start_measurements() override;
146
147
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
148
149
// set device type within a device class
150
void set_device_type(uint8_t devtype) override;
151
152
// return 24 bit bus identifier
153
uint32_t get_bus_id(void) const override;
154
155
private:
156
AuxiliaryBus *_bus;
157
AuxiliaryBusSlave *_slave;
158
bool _started;
159
};
160
#endif // AP_INERTIALSENSOR_ENABLED
161
162
#endif // AP_COMPASS_HMC5843_ENABLED
163
164