APM:Libraries
libraries
AP_InertialSensor
AP_InertialSensor_BMI160.h
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2016 Intel Corporation. All rights reserved.
3
*
4
* This file is free software: you can redistribute it and/or modify it
5
* under the terms of the GNU General Public License as published by the
6
* Free Software Foundation, either version 3 of the License, or
7
* (at your option) any later version.
8
*
9
* This file is distributed in the hope that it will be useful, but
10
* WITHOUT ANY WARRANTY; without even the implied warranty of
11
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12
* See the GNU General Public License for more details.
13
*
14
* You should have received a copy of the GNU General Public License along
15
* with this program. If not, see <http://www.gnu.org/licenses/>.
16
*/
17
#pragma once
18
19
#include <
AP_HAL/AP_HAL.h
>
20
21
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
22
23
#include "
AP_InertialSensor.h
"
24
#include "
AP_InertialSensor_Backend.h
"
25
26
class
AP_InertialSensor_BMI160
:
public
AP_InertialSensor_Backend
{
27
public
:
28
static
AP_InertialSensor_Backend
*
probe
(
AP_InertialSensor
&imu,
29
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
dev
);
30
34
void
start
()
override
;
35
36
bool
update
()
override
;
37
38
private
:
39
AP_InertialSensor_BMI160
(
AP_InertialSensor
&imu,
40
AP_HAL::OwnPtr<AP_HAL::Device>
dev);
41
47
void
_check_err_reg
();
48
56
bool
_hardware_init
();
57
65
bool
_init
();
66
73
bool
_configure_accel
();
74
81
bool
_configure_gyro
();
82
89
bool
_configure_int1_pin
();
90
96
bool
_configure_fifo
();
97
101
void
_poll_data
();
102
106
void
_read_fifo
();
107
108
AP_HAL::OwnPtr<AP_HAL::Device>
_dev
;
109
110
uint8_t
_accel_instance
;
111
float
_accel_scale
;
112
113
uint8_t
_gyro_instance
;
114
float
_gyro_scale
;
115
116
AP_HAL::DigitalSource
*
_int1_pin
;
117
};
118
119
#endif
AP_InertialSensor_BMI160::_configure_int1_pin
bool _configure_int1_pin()
Definition:
AP_InertialSensor_BMI160.cpp:267
AP_HAL.h
AP_InertialSensor_BMI160::_configure_gyro
bool _configure_gyro()
Definition:
AP_InertialSensor_BMI160.cpp:241
AP_InertialSensor_BMI160::_dev
AP_HAL::OwnPtr< AP_HAL::Device > _dev
Definition:
AP_InertialSensor_BMI160.h:108
AP_InertialSensor_BMI160::_int1_pin
AP_HAL::DigitalSource * _int1_pin
Definition:
AP_InertialSensor_BMI160.h:116
AP_InertialSensor.h
AP_HAL::OwnPtr< AP_HAL::SPIDevice >
AP_InertialSensor_Backend
Definition:
AP_InertialSensor_Backend.h:41
AP_InertialSensor_BMI160::_accel_scale
float _accel_scale
Definition:
AP_InertialSensor_BMI160.h:111
AP_InertialSensor_BMI160::_gyro_scale
float _gyro_scale
Definition:
AP_InertialSensor_BMI160.h:114
AP_InertialSensor
Definition:
AP_InertialSensor.h:47
dev
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition:
ICM20789.cpp:16
AP_InertialSensor_BMI160::_gyro_instance
uint8_t _gyro_instance
Definition:
AP_InertialSensor_BMI160.h:113
AP_InertialSensor_BMI160::_accel_instance
uint8_t _accel_instance
Definition:
AP_InertialSensor_BMI160.h:110
AP_InertialSensor_BMI160::_init
bool _init()
Definition:
AP_InertialSensor_BMI160.cpp:487
AP_InertialSensor_BMI160::_check_err_reg
void _check_err_reg()
Definition:
AP_InertialSensor_BMI160.cpp:198
AP_InertialSensor_BMI160::_configure_fifo
bool _configure_fifo()
Definition:
AP_InertialSensor_BMI160.cpp:303
AP_InertialSensor_BMI160
Definition:
AP_InertialSensor_BMI160.h:26
AP_InertialSensor_BMI160::_configure_accel
bool _configure_accel()
Definition:
AP_InertialSensor_BMI160.cpp:214
AP_InertialSensor_BMI160::start
void start() override
Definition:
AP_InertialSensor_BMI160.cpp:151
AP_InertialSensor_Backend.h
AP_InertialSensor_BMI160::AP_InertialSensor_BMI160
AP_InertialSensor_BMI160(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::Device > dev)
Definition:
AP_InertialSensor_BMI160.cpp:123
AP_HAL::DigitalSource
Definition:
GPIO.h:16
AP_InertialSensor_BMI160::update
bool update() override
Definition:
AP_InertialSensor_BMI160.cpp:191
AP_InertialSensor_BMI160::_poll_data
void _poll_data()
Definition:
AP_InertialSensor_BMI160.cpp:420
AP_InertialSensor_BMI160::_read_fifo
void _read_fifo()
Definition:
AP_InertialSensor_BMI160.cpp:335
AP_InertialSensor_BMI160::probe
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev)
Definition:
AP_InertialSensor_BMI160.cpp:131
AP_InertialSensor_BMI160::_hardware_init
bool _hardware_init()
Definition:
AP_InertialSensor_BMI160.cpp:425
Generated on Sun Jun 17 2018 14:18:49 for APM:Libraries by
1.8.13