APM:Libraries
libraries
AP_Compass
AP_Compass_LIS3MDL.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/Device.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_LIS3MDL_I2C_ADDR
26
# define HAL_COMPASS_LIS3MDL_I2C_ADDR 0x1c
27
#endif
28
29
#ifndef HAL_COMPASS_LIS3MDL_I2C_ADDR2
30
# define HAL_COMPASS_LIS3MDL_I2C_ADDR2 0x1e
31
#endif
32
33
class
AP_Compass_LIS3MDL
:
public
AP_Compass_Backend
34
{
35
public
:
36
static
AP_Compass_Backend
*
probe
(
Compass
&
compass
,
37
AP_HAL::OwnPtr<AP_HAL::Device>
dev
,
38
bool
force_external
=
false
,
39
enum
Rotation
rotation
=
ROTATION_NONE
);
40
41
void
read
()
override
;
42
43
static
constexpr
const
char
*
name
=
"LIS3MDL"
;
44
45
private
:
46
AP_Compass_LIS3MDL
(
Compass
&compass,
AP_HAL::OwnPtr<AP_HAL::Device>
dev,
47
bool
force_external
,
48
enum
Rotation
rotation
);
49
50
AP_HAL::OwnPtr<AP_HAL::Device>
dev
;
51
55
bool
init
();
56
void
timer
();
57
58
uint8_t
compass_instance
;
59
Vector3f
accum
;
60
uint16_t
accum_count
;
61
bool
force_external
;
62
enum
Rotation
rotation
;
63
};
AP_Compass_LIS3MDL::timer
void timer()
Definition:
AP_Compass_LIS3MDL.cpp:137
AP_HAL.h
ROTATION_NONE
Definition:
rotations.h:28
AP_Compass_Backend
Definition:
AP_Compass_Backend.h:25
AP_Compass_LIS3MDL::probe
static AP_Compass_Backend * probe(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external=false, enum Rotation rotation=ROTATION_NONE)
Definition:
AP_Compass_LIS3MDL.cpp:51
AP_Compass_LIS3MDL::name
static constexpr const char * name
Definition:
AP_Compass_LIS3MDL.h:43
Rotation
Rotation
Definition:
rotations.h:27
AP_HAL::OwnPtr< AP_HAL::Device >
AP_Compass_LIS3MDL::force_external
bool force_external
Definition:
AP_Compass_LIS3MDL.h:61
AP_Compass_LIS3MDL::AP_Compass_LIS3MDL
AP_Compass_LIS3MDL(Compass &compass, AP_HAL::OwnPtr< AP_HAL::Device > dev, bool force_external, enum Rotation rotation)
Definition:
AP_Compass_LIS3MDL.cpp:68
constexpr
#define constexpr
Definition:
AP_HAL_Macros.h:16
AP_Compass_LIS3MDL::dev
AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition:
AP_Compass_LIS3MDL.h:50
Compass
Definition:
AP_Compass.h:49
AP_Compass_LIS3MDL::read
void read() override
Definition:
AP_Compass_LIS3MDL.cpp:182
AP_Math.h
compass
static Compass compass
Definition:
AHRS_Test.cpp:20
AP_Compass_LIS3MDL::init
bool init()
Definition:
AP_Compass_LIS3MDL.cpp:79
AP_Compass.h
AP_Common.h
Common definitions and utility routines for the ArduPilot libraries.
AP_Compass_Backend.h
Device.h
AP_Compass_LIS3MDL
Definition:
AP_Compass_LIS3MDL.h:33
Vector3< float >
AP_Compass_LIS3MDL::accum_count
uint16_t accum_count
Definition:
AP_Compass_LIS3MDL.h:60
AP_Compass_LIS3MDL::accum
Vector3f accum
Definition:
AP_Compass_LIS3MDL.h:59
AP_Compass_LIS3MDL::rotation
enum Rotation rotation
Definition:
AP_Compass_LIS3MDL.h:62
AP_Compass_LIS3MDL::compass_instance
uint8_t compass_instance
Definition:
AP_Compass_LIS3MDL.h:58
Generated on Sun Jun 17 2018 14:18:48 for APM:Libraries by
1.8.13