APM:Libraries
libraries
AP_Compass
AP_Compass_MMC3416.h
Go to the documentation of this file.
1
/*
2
* This file is free software: you can redistribute it and/or modify it
3
* under the terms of the GNU General Public License as published by the
4
* Free Software Foundation, either version 3 of the License, or
5
* (at your option) any later version.
6
*
7
* This file is distributed in the hope that it will be useful, but
8
* WITHOUT ANY WARRANTY; without even the implied warranty of
9
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10
* See the GNU General Public License for more details.
11
*
12
* You should have received a copy of the GNU General Public License along
13
* with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
#pragma once
16
17
#include <
AP_Common/AP_Common.h
>
18
#include <
AP_HAL/AP_HAL.h
>
19
#include <
AP_HAL/I2CDevice.h
>
20
#include <
AP_Math/AP_Math.h
>
21
22
#include "
AP_Compass.h
"
23
#include "
AP_Compass_Backend.h
"
24
25
#ifndef HAL_COMPASS_MMC3416_I2C_ADDR
26
# define HAL_COMPASS_MMC3416_I2C_ADDR 0x30
27
#endif
28
29
class
AP_Compass_MMC3416
:
public
AP_Compass_Backend
30
{
31
public
:
32
static
AP_Compass_Backend
*
probe
(
Compass
&
compass
,
33
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
dev
,
34
bool
force_external
=
false
,
35
enum
Rotation
rotation
=
ROTATION_NONE
);
36
37
void
read
()
override
;
38
39
static
constexpr
const
char
*
name
=
"MMC3416"
;
40
41
private
:
42
AP_Compass_MMC3416
(
Compass
&compass,
AP_HAL::OwnPtr<AP_HAL::Device>
dev,
43
bool
force_external
,
44
enum
Rotation
rotation
);
45
46
AP_HAL::OwnPtr<AP_HAL::Device>
dev
;
47
48
enum
{
49
STATE_REFILL1
,
50
STATE_REFILL1_WAIT
,
51
STATE_MEASURE_WAIT1
,
52
STATE_REFILL2_WAIT
,
53
STATE_MEASURE_WAIT2
,
54
STATE_MEASURE_WAIT3
,
55
}
state
;
56
60
bool
init
();
61
void
timer
();
62
void
accumulate_field
(
Vector3f
&field);
63
64
uint8_t
compass_instance
;
65
Vector3f
accum
;
66
uint16_t
accum_count
;
67
bool
force_external
;
68
Vector3f
offset
;
69
uint16_t
measure_count
;
70
bool
have_initial_offset
;
71
uint32_t
refill_start_ms
;
72
uint32_t
last_sample_ms
;
73
74
uint16_t
data0
[3];
75
76
enum
Rotation
rotation
;
77
};
AP_Compass_MMC3416::STATE_REFILL1
Definition:
AP_Compass_MMC3416.h:49
AP_Compass_MMC3416::have_initial_offset
bool have_initial_offset
Definition:
AP_Compass_MMC3416.h:70
AP_Compass_MMC3416::last_sample_ms
uint32_t last_sample_ms
Definition:
AP_Compass_MMC3416.h:72
AP_Compass_MMC3416::AP_Compass_MMC3416
AP_Compass_MMC3416(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external, enum Rotation rotation)
Definition:
AP_Compass_MMC3416.cpp:61
AP_Compass_MMC3416::probe
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
Definition:
AP_Compass_MMC3416.cpp:44
AP_Compass_MMC3416::init
bool init()
Definition:
AP_Compass_MMC3416.cpp:72
AP_HAL.h
ROTATION_NONE
Definition:
rotations.h:28
AP_Compass_Backend
Definition:
AP_Compass_Backend.h:25
AP_Compass_MMC3416
Definition:
AP_Compass_MMC3416.h:29
AP_Compass_MMC3416::accum_count
uint16_t accum_count
Definition:
AP_Compass_MMC3416.h:66
I2CDevice.h
AP_Compass_MMC3416::refill_start_ms
uint32_t refill_start_ms
Definition:
AP_Compass_MMC3416.h:71
AP_Compass_MMC3416::name
static constexpr const char * name
Definition:
AP_Compass_MMC3416.h:39
AP_Compass_MMC3416::accumulate_field
void accumulate_field(Vector3f &field)
Definition:
AP_Compass_MMC3416.cpp:288
AP_Compass_MMC3416::STATE_REFILL1_WAIT
Definition:
AP_Compass_MMC3416.h:50
Rotation
Rotation
Definition:
rotations.h:27
AP_Compass_MMC3416::read
void read() override
Definition:
AP_Compass_MMC3416.cpp:315
AP_HAL::OwnPtr< AP_HAL::I2CDevice >
AP_Compass_MMC3416::state
enum AP_Compass_MMC3416::@19 state
AP_Compass_MMC3416::STATE_REFILL2_WAIT
Definition:
AP_Compass_MMC3416.h:52
AP_Compass_MMC3416::force_external
bool force_external
Definition:
AP_Compass_MMC3416.h:67
constexpr
#define constexpr
Definition:
AP_HAL_Macros.h:16
AP_Compass_MMC3416::STATE_MEASURE_WAIT2
Definition:
AP_Compass_MMC3416.h:53
AP_Compass_MMC3416::accum
Vector3f accum
Definition:
AP_Compass_MMC3416.h:65
Compass
Definition:
AP_Compass.h:49
AP_Compass_MMC3416::dev
AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition:
AP_Compass_MMC3416.h:46
AP_Compass_MMC3416::data0
uint16_t data0[3]
Definition:
AP_Compass_MMC3416.h:74
AP_Compass_MMC3416::STATE_MEASURE_WAIT1
Definition:
AP_Compass_MMC3416.h:51
AP_Compass_MMC3416::compass_instance
uint8_t compass_instance
Definition:
AP_Compass_MMC3416.h:64
AP_Math.h
AP_Compass_MMC3416::measure_count
uint16_t measure_count
Definition:
AP_Compass_MMC3416.h:69
compass
static Compass compass
Definition:
AHRS_Test.cpp:20
AP_Compass.h
AP_Common.h
Common definitions and utility routines for the ArduPilot libraries.
AP_Compass_Backend.h
AP_Compass_MMC3416::STATE_MEASURE_WAIT3
Definition:
AP_Compass_MMC3416.h:54
Vector3< float >
AP_Compass_MMC3416::offset
Vector3f offset
Definition:
AP_Compass_MMC3416.h:68
AP_Compass_MMC3416::rotation
enum Rotation rotation
Definition:
AP_Compass_MMC3416.h:76
AP_Compass_MMC3416::timer
void timer()
Definition:
AP_Compass_MMC3416.cpp:123
Generated on Sun Jun 17 2018 14:18:48 for APM:Libraries by
1.8.13