APM:Libraries
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>
10 
11 #include "AP_InertialSensor.h"
13 
15 {
16 public:
20  enum Rotation rotation_a,
21  enum Rotation rotation_g);
22 
23  virtual ~AP_InertialSensor_RST();
24 
25  // probe the sensor on SPI bus
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 
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;
55 };
56 #endif
Rotation
Definition: rotations.h:27
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_accel
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_gyro
A class to implement a second order low pass filter.
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)
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)