31 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX 41 #define ADXL345_ACCELEROMETER_ADDRESS 0x53 42 #define ADXL345_ACCELEROMETER_XL345_DEVID 0xe5 43 #define ADXL345_ACCELEROMETER_ADXLREG_BW_RATE 0x2c 44 #define ADXL345_ACCELEROMETER_ADXLREG_POWER_CTL 0x2d 45 #define ADXL345_ACCELEROMETER_ADXLREG_DATA_FORMAT 0x31 46 #define ADXL345_ACCELEROMETER_ADXLREG_DEVID 0x00 47 #define ADXL345_ACCELEROMETER_ADXLREG_DATAX0 0x32 48 #define ADXL345_ACCELEROMETER_ADXLREG_FIFO_CTL 0x38 49 #define ADXL345_ACCELEROMETER_ADXLREG_FIFO_CTL_STREAM 0x9F 50 #define ADXL345_ACCELEROMETER_ADXLREG_FIFO_STATUS 0x39 55 #define ADXL345_ACCELEROMETER_SCALE_M_S (GRAVITY_MSS / 256.0f) 58 #define L3G4200D_I2C_ADDRESS 0x69 60 #define L3G4200D_REG_WHO_AM_I 0x0f 61 #define L3G4200D_REG_WHO_AM_I_VALUE 0xd3 63 #define L3G4200D_REG_CTRL_REG1 0x20 64 #define L3G4200D_REG_CTRL_REG1_DRBW_800_110 0xf0 65 #define L3G4200D_REG_CTRL_REG1_PD 0x08 66 #define L3G4200D_REG_CTRL_REG1_XYZ_ENABLE 0x07 68 #define L3G4200D_REG_CTRL_REG4 0x23 69 #define L3G4200D_REG_CTRL_REG4_FS_2000 0x30 71 #define L3G4200D_REG_CTRL_REG5 0x24 72 #define L3G4200D_REG_CTRL_REG5_FIFO_EN 0x40 74 #define L3G4200D_REG_FIFO_CTL 0x2e 75 #define L3G4200D_REG_FIFO_CTL_STREAM 0x40 77 #define L3G4200D_REG_FIFO_SRC 0x2f 78 #define L3G4200D_REG_FIFO_SRC_ENTRIES_MASK 0x1f 79 #define L3G4200D_REG_FIFO_SRC_EMPTY 0x20 80 #define L3G4200D_REG_FIFO_SRC_OVERRUN 0x40 82 #define L3G4200D_REG_XL 0x28 85 #define L3G4200D_REG_AUTO_INCREMENT 0x80 90 #define L3G4200D_GYRO_SCALE_R_S (DEG_TO_RAD * 70.0f * 0.001f) 133 AP_HAL::panic(
"AP_InertialSensor_L3G4200D: could not find ADXL345 accelerometer sensor");
163 AP_HAL::panic(
"AP_InertialSensor_L3G4200D: could not find L3G4200D gyro sensor");
231 uint8_t num_samples_available;
232 uint8_t fifo_status = 0;
239 num_samples_available = 32;
242 num_samples_available = 0;
248 if (num_samples_available > 0) {
250 int16_t
buffer[num_samples_available][3];
252 (uint8_t *)&buffer,
sizeof(buffer))) {
253 for (uint8_t i=0; i < num_samples_available; i++) {
266 num_samples_available = fifo_status & 0x3F;
269 if (num_samples_available > 0) {
270 int16_t
buffer[num_samples_available][3];
272 (uint8_t *)buffer,
sizeof(buffer[0]),
273 num_samples_available)) {
274 for (uint8_t i=0; i<num_samples_available; i++) {
#define L3G4200D_REG_FIFO_CTL
#define ADXL345_ACCELEROMETER_XL345_DEVID
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
Vector3< float > Vector3f
#define ADXL345_ACCELEROMETER_ADXLREG_DATA_FORMAT
#define L3G4200D_REG_AUTO_INCREMENT
#define L3G4200D_REG_CTRL_REG1_PD
#define L3G4200D_GYRO_SCALE_R_S
static uint8_t buffer[SRXL_FRAMELEN_MAX]
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
#define L3G4200D_REG_CTRL_REG5_FIFO_EN
virtual Semaphore * get_semaphore() override=0
#define L3G4200D_REG_WHO_AM_I
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define L3G4200D_REG_CTRL_REG4_FS_2000
#define ADXL345_ACCELEROMETER_ADXLREG_DATAX0
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define L3G4200D_REG_CTRL_REG1
#define L3G4200D_REG_CTRL_REG4
uint32_t get_bus_id_devtype(uint8_t devtype)
#define ADXL345_ACCELEROMETER_ADXLREG_FIFO_CTL_STREAM
AP_HAL::OwnPtr< AP_HAL::Device > _dev
#define ADXL345_ACCELEROMETER_ADXLREG_FIFO_CTL
#define L3G4200D_REG_FIFO_CTL_STREAM
virtual void delay(uint16_t ms)=0
#define L3G4200D_REG_CTRL_REG5
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
#define L3G4200D_REG_FIFO_SRC_OVERRUN
#define L3G4200D_REG_FIFO_SRC_EMPTY
static AP_HAL::OwnPtr< AP_HAL::Device > dev
#define ADXL345_ACCELEROMETER_ADXLREG_POWER_CTL
#define ADXL345_ACCELEROMETER_ADXLREG_DEVID
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0)
#define L3G4200D_REG_WHO_AM_I_VALUE
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
#define ADXL345_ACCELEROMETER_ADXLREG_BW_RATE
virtual bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times)=0
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
#define L3G4200D_REG_FIFO_SRC
void start(void) override
#define ADXL345_ACCELEROMETER_ADXLREG_FIFO_STATUS
void update_gyro(uint8_t instance)
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
#define ADXL345_ACCELEROMETER_SCALE_M_S
AP_InertialSensor_L3G4200D(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
void panic(const char *errormsg,...) FMT_PRINTF(1
#define L3G4200D_REG_CTRL_REG1_DRBW_800_110
virtual ~AP_InertialSensor_L3G4200D()
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
#define L3G4200D_REG_CTRL_REG1_XYZ_ENABLE
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
void update_accel(uint8_t instance)
AP_HAL::Scheduler * scheduler
#define L3G4200D_REG_FIFO_SRC_ENTRIES_MASK