APM:Libraries
libraries
AP_InertialSensor
AP_InertialSensor_RST.h
Go to the documentation of this file.
1
#pragma once
2
3
#include <
AP_HAL/AP_HAL.h
>
4
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
5
6
#include <
AP_HAL/I2CDevice.h
>
7
#include <
AP_HAL/SPIDevice.h
>
8
#include <
Filter/Filter.h
>
9
#include <
Filter/LowPassFilter2p.h
>
10
11
#include "
AP_InertialSensor.h
"
12
#include "
AP_InertialSensor_Backend.h
"
13
14
class
AP_InertialSensor_RST
:
public
AP_InertialSensor_Backend
15
{
16
public
:
17
AP_InertialSensor_RST
(
AP_InertialSensor
&imu,
18
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
dev_gyro,
19
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
dev_accel,
20
enum
Rotation
rotation_a,
21
enum
Rotation
rotation_g);
22
23
virtual
~AP_InertialSensor_RST
();
24
25
// probe the sensor on SPI bus
26
static
AP_InertialSensor_Backend
*
probe
(
AP_InertialSensor
&imu,
27
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
dev_gyro,
28
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
dev_accel,
29
enum
Rotation
rotation_a,
30
enum
Rotation
rotation_g);
31
32
/* update accel and gyro state */
33
bool
update
()
override
;
34
35
void
start
(
void
)
override
;
36
37
private
:
38
bool
_init_sensor
();
39
bool
_init_gyro
();
40
bool
_init_accel
();
41
void
gyro_measure
();
42
void
accel_measure
();
43
44
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
_dev_gyro
;
//i3g4250d
45
AP_HAL::OwnPtr<AP_HAL::SPIDevice>
_dev_accel
;
//iis328dq
46
47
float
_gyro_scale
;
48
float
_accel_scale
;
49
50
// gyro and accel instances
51
uint8_t
_gyro_instance
;
52
uint8_t
_accel_instance
;
53
enum
Rotation
_rotation_g
;
54
enum
Rotation
_rotation_a
;
55
};
56
#endif
AP_InertialSensor_RST
Definition:
AP_InertialSensor_RST.h:14
SPIDevice.h
AP_InertialSensor_RST::_gyro_scale
float _gyro_scale
Definition:
AP_InertialSensor_RST.h:47
AP_HAL.h
AP_InertialSensor_RST::_accel_scale
float _accel_scale
Definition:
AP_InertialSensor_RST.h:48
I2CDevice.h
AP_InertialSensor_RST::_gyro_instance
uint8_t _gyro_instance
Definition:
AP_InertialSensor_RST.h:51
Filter.h
Rotation
Rotation
Definition:
rotations.h:27
AP_InertialSensor.h
AP_HAL::OwnPtr< AP_HAL::SPIDevice >
AP_InertialSensor_RST::_init_gyro
bool _init_gyro()
Definition:
AP_InertialSensor_RST.cpp:221
AP_InertialSensor_RST::_dev_accel
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_accel
Definition:
AP_InertialSensor_RST.h:45
AP_InertialSensor_Backend
Definition:
AP_InertialSensor_Backend.h:41
AP_InertialSensor_RST::gyro_measure
void gyro_measure()
Definition:
AP_InertialSensor_RST.cpp:366
AP_InertialSensor
Definition:
AP_InertialSensor.h:47
AP_InertialSensor_RST::~AP_InertialSensor_RST
virtual ~AP_InertialSensor_RST()
Definition:
AP_InertialSensor_RST.cpp:192
AP_InertialSensor_RST::start
void start(void) override
Definition:
AP_InertialSensor_RST.cpp:341
AP_InertialSensor_RST::update
bool update() override
Definition:
AP_InertialSensor_RST.cpp:357
AP_InertialSensor_RST::_dev_gyro
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_gyro
Definition:
AP_InertialSensor_RST.h:44
LowPassFilter2p.h
A class to implement a second order low pass filter.
AP_InertialSensor_RST::_accel_instance
uint8_t _accel_instance
Definition:
AP_InertialSensor_RST.h:52
AP_InertialSensor_Backend.h
AP_InertialSensor_RST::_rotation_a
enum Rotation _rotation_a
Definition:
AP_InertialSensor_RST.h:54
AP_InertialSensor_RST::probe
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a, enum Rotation rotation_g)
Definition:
AP_InertialSensor_RST.cpp:199
AP_InertialSensor_RST::_rotation_g
enum Rotation _rotation_g
Definition:
AP_InertialSensor_RST.h:53
AP_InertialSensor_RST::_init_accel
bool _init_accel()
Definition:
AP_InertialSensor_RST.cpp:284
AP_InertialSensor_RST::accel_measure
void accel_measure()
Definition:
AP_InertialSensor_RST.cpp:387
AP_InertialSensor_RST::AP_InertialSensor_RST
AP_InertialSensor_RST(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a, enum Rotation rotation_g)
Definition:
AP_InertialSensor_RST.cpp:179
AP_InertialSensor_RST::_init_sensor
bool _init_sensor()
Definition:
AP_InertialSensor_RST.cpp:329
Generated on Sun Jun 17 2018 14:18:49 for APM:Libraries by
1.8.13