20 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ 31 #define ADDR_INCREMENT (1<<6) 34 #define ACCEL_WHO_AM_I 0x0F 35 #define ACCEL_WHO_I_AM 0x32 37 #define ACCEL_CTRL_REG1 0x20 39 #define RATE_50HZ_LP_37HZ (0<<4) | (0<<3) 40 #define RATE_100HZ_LP_74HZ (0<<4) | (1<<3) 41 #define RATE_400HZ_LP_292HZ (1<<4) | (0<<3) 42 #define RATE_1000HZ_LP_780HZ (1<<4) | (1<<3) 44 #define ACCEL_CTRL_REG2 0x21 45 #define ACCEL_CTRL_REG3 0x22 46 #define ACCEL_CTRL_REG4 0x23 48 #define ACCEL_CTRL_REG5 0x24 49 #define ACCEL_HP_FILTER_RESETE 0x25 50 #define ACCEL_OUT_REFERENCE 0x26 51 #define ACCEL_STATUS_REG 0x27 52 #define ACCEL_OUT_X_L 0x28 53 #define ACCEL_OUT_X_H 0x29 54 #define ACCEL_OUT_Y_L 0x2A 55 #define ACCEL_OUT_Y_H 0x2B 56 #define ACCEL_OUT_Z_L 0x2C 57 #define ACCEL_OUT_Z_H 0x2D 58 #define ACCEL_INT1_CFG 0x30 59 #define ACCEL_INT1_SRC 0x31 60 #define ACCEL_INT1_TSH 0x32 61 #define ACCEL_INT1_DURATION 0x33 62 #define ACCEL_INT2_CFG 0x34 63 #define ACCEL_INT2_SRC 0x35 64 #define ACCEL_INT2_TSH 0x36 65 #define ACCEL_INT2_DURATION 0x37 69 #define ACCEL_REG1_POWER_NORMAL ((0<<7) | (0<<6) | (1<<5)) 70 #define ACCEL_REG1_Z_ENABLE (1<<2) 71 #define ACCEL_REG1_Y_ENABLE (1<<1) 72 #define ACCEL_REG1_X_ENABLE (1<<0) 74 #define ACCEL_REG4_BDU (1<<7) 75 #define ACCEL_REG4_BLE (1<<6) 76 #define ACCEL_REG4_FULL_SCALE_BITS ((1<<5) | (1<<4)) 77 #define ACCEL_REG4_FULL_SCALE_2G ((0<<5) | (0<<4)) 78 #define ACCEL_REG4_FULL_SCALE_4G ((0<<5) | (1<<4)) 79 #define ACCEL_REG4_FULL_SCALE_8G ((1<<5) | (1<<4)) 81 #define ACCEL_STATUS_ZYXOR (1<<7) 82 #define ACCEL_STATUS_ZOR (1<<6) 83 #define ACCEL_STATUS_YOR (1<<5) 84 #define ACCEL_STATUS_XOR (1<<4) 85 #define ACCEL_STATUS_ZYXDA (1<<3) 86 #define ACCEL_STATUS_ZDA (1<<2) 87 #define ACCEL_STATUS_YDA (1<<1) 88 #define ACCEL_STATUS_XDA (1<<0) 90 #define ACCEL_DEFAULT_RANGE_G 8 91 #define ACCEL_DEFAULT_RATE 1000 92 #define ACCEL_DEFAULT_ONCHIP_FILTER_FREQ 780 93 #define ACCEL_ONE_G 9.80665f 96 #define GYRO_WHO_AM_I 0x0F 97 #define GYRO_WHO_I_AM 0xD3 99 #define GYRO_CTRL_REG1 0x20 101 #define RATE_100HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4)) 102 #define RATE_200HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4)) 103 #define RATE_200HZ_LP_50HZ ((0<<7) | (1<<6) | (1<<5) | (0<<4)) 104 #define RATE_200HZ_LP_70HZ ((0<<7) | (1<<6) | (1<<5) | (1<<4)) 105 #define RATE_400HZ_LP_20HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4)) 106 #define RATE_400HZ_LP_25HZ ((1<<7) | (0<<6) | (0<<5) | (1<<4)) 107 #define RATE_400HZ_LP_50HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4)) 108 #define RATE_400HZ_LP_100HZ ((1<<7) | (0<<6) | (1<<5) | (1<<4)) 109 #define RATE_800HZ_LP_30HZ ((1<<7) | (1<<6) | (0<<5) | (0<<4)) 110 #define RATE_800HZ_LP_35HZ ((1<<7) | (1<<6) | (0<<5) | (1<<4)) 111 #define RATE_800HZ_LP_50HZ ((1<<7) | (1<<6) | (1<<5) | (0<<4)) 112 #define RATE_800HZ_LP_100HZ ((1<<7) | (1<<6) | (1<<5) | (1<<4)) 114 #define GYRO_CTRL_REG2 0x21 115 #define GYRO_CTRL_REG3 0x22 116 #define GYRO_CTRL_REG4 0x23 117 #define RANGE_250DPS (0<<4) 118 #define RANGE_500DPS (1<<4) 119 #define RANGE_2000DPS (3<<4) 121 #define GYRO_CTRL_REG5 0x24 122 #define GYRO_REFERENCE 0x25 123 #define GYRO_OUT_TEMP 0x26 124 #define GYRO_STATUS_REG 0x27 125 #define GYRO_OUT_X_L 0x28 126 #define GYRO_OUT_X_H 0x29 127 #define GYRO_OUT_Y_L 0x2A 128 #define GYRO_OUT_Y_H 0x2B 129 #define GYRO_OUT_Z_L 0x2C 130 #define GYRO_OUT_Z_H 0x2D 131 #define GYRO_FIFO_CTRL_REG 0x2E 132 #define GYRO_FIFO_SRC_REG 0x2F 133 #define GYRO_INT1_CFG 0x30 134 #define GYRO_INT1_SRC 0x31 135 #define GYRO_INT1_TSH_XH 0x32 136 #define GYRO_INT1_TSH_XL 0x33 137 #define GYRO_INT1_TSH_YH 0x34 138 #define GYRO_INT1_TSH_YL 0x35 139 #define GYRO_INT1_TSH_ZH 0x36 140 #define GYRO_INT1_TSH_ZL 0x37 141 #define GYRO_INT1_DURATION 0x38 142 #define GYRO_LOW_ODR 0x39 146 #define GYRO_REG1_POWER_NORMAL (1<<3) 147 #define GYRO_REG1_Z_ENABLE (1<<2) 148 #define GYRO_REG1_Y_ENABLE (1<<1) 149 #define GYRO_REG1_X_ENABLE (1<<0) 151 #define GYRO_REG4_BLE (1<<6) 153 #define GYRO_REG5_FIFO_ENABLE (1<<6) 154 #define GYRO_REG5_REBOOT_MEMORY (1<<7) 156 #define GYRO_STATUS_ZYXOR (1<<7) 157 #define GYRO_STATUS_ZOR (1<<6) 158 #define GYRO_STATUS_YOR (1<<5) 159 #define GYRO_STATUS_XOR (1<<4) 160 #define GYRO_STATUS_ZYXDA (1<<3) 161 #define GYRO_STATUS_ZDA (1<<2) 162 #define GYRO_STATUS_YDA (1<<1) 163 #define GYRO_STATUS_XDA (1<<0) 165 #define GYRO_FIFO_CTRL_BYPASS_MODE (0<<5) 166 #define GYRO_FIFO_CTRL_FIFO_MODE (1<<5) 167 #define GYRO_FIFO_CTRL_STREAM_MODE (1<<6) 168 #define GYRO_FIFO_CTRL_STREAM_TO_FIFO_MODE (3<<5) 169 #define GYRO_FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7) 172 #define GYRO_DEFAULT_RATE 800 173 #define GYRO_DEFAULT_RANGE_DPS 2000 174 #define GYRO_DEFAULT_FILTER_FREQ 35 175 #define GYRO_TEMP_OFFSET_CELSIUS 40 185 , _dev_gyro(
std::move(dev_gyro))
186 , _dev_accel(
std::move(dev_accel))
187 , _rotation_g(rotation_g)
188 , _rotation_a(rotation_a)
205 if (!dev_gyro && !dev_accel) {
236 hal.
console->
printf(
"RST: unexpected gyro WHOAMI 0x%x\n", (
unsigned)whoami);
237 printf(
"RST: unexpected gyro WHOAMI 0x%x\n", (
unsigned)whoami);
241 printf(
"detect i3g4250d\n");
298 hal.
console->
printf(
"RST: unexpected accel WHOAMI 0x%x\n", (
unsigned)whoami);
299 printf(
"RST: unexpected accel WHOAMI 0x%x\n", (
unsigned)whoami);
379 gyro =
Vector3f(raw_data[0], raw_data[1], raw_data[2]);
400 accel =
Vector3f(raw_data[0], raw_data[1], raw_data[2]);
#define ACCEL_REG4_FULL_SCALE_8G
int printf(const char *fmt,...)
void set_gyro_orientation(uint8_t instance, enum Rotation rotation)
#define RATE_800HZ_LP_50HZ
Vector3< float > Vector3f
#define ACCEL_REG1_Z_ENABLE
#define ACCEL_REG1_Y_ENABLE
AP_HAL::UARTDriver * console
#define GYRO_STATUS_ZYXDA
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define ACCEL_REG1_POWER_NORMAL
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
#define GYRO_REG1_Y_ENABLE
#define GYRO_REG1_X_ENABLE
#define GYRO_FIFO_CTRL_REG
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define GYRO_REG1_POWER_NORMAL
uint32_t get_bus_id_devtype(uint8_t devtype)
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_accel
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
virtual Semaphore * get_semaphore() override=0
virtual ~AP_InertialSensor_RST()
void start(void) override
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0)
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
#define GYRO_REG1_Z_ENABLE
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev_gyro
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
virtual bool set_speed(Device::Speed speed) override=0
#define RATE_1000HZ_LP_780HZ
void set_read_flag(uint8_t flag)
void set_accel_orientation(uint8_t instance, enum Rotation rotation)
#define ACCEL_STATUS_ZYXDA
void update_gyro(uint8_t instance)
#define GYRO_REG5_FIFO_ENABLE
enum Rotation _rotation_a
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)
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
enum Rotation _rotation_g
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
#define ACCEL_REG1_X_ENABLE
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
void update_accel(uint8_t instance)
#define GYRO_FIFO_CTRL_BYPASS_MODE
AP_HAL::Scheduler * scheduler
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)