Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
Driver for the PX4FMU SPI1 for the MPU6000 and I2C2 for the HMC5883. More...
#include "std.h"
#include "generated/airframe.h"
#include "modules/imu/imu.h"
#include "peripherals/mpu60x0_spi.h"
#include "peripherals/hmc58xx.h"
Go to the source code of this file.
Data Structures | |
struct | ImuPx4fmu |
Macros | |
#define | PX4FMU_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 |
#define | PX4FMU_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G |
Functions | |
void | imu_px4fmu_init (void) |
void | imu_px4fmu_periodic (void) |
void | imu_px4fmu_event (void) |
Variables | |
struct ImuPx4fmu | imu_px4fmu |
Driver for the PX4FMU SPI1 for the MPU6000 and I2C2 for the HMC5883.
Definition in file imu_px4fmu.h.
struct ImuPx4fmu |
Definition at line 45 of file imu_px4fmu.h.
Data Fields | ||
---|---|---|
struct Hmc58xx | hmc | |
struct Mpu60x0_Spi | mpu |
#define PX4FMU_ACCEL_RANGE MPU60X0_ACCEL_RANGE_16G |
Definition at line 42 of file imu_px4fmu.h.
#define PX4FMU_GYRO_RANGE MPU60X0_GYRO_RANGE_2000 |
Definition at line 38 of file imu_px4fmu.h.
void imu_px4fmu_event | ( | void | ) |
Definition at line 90 of file imu_px4fmu.c.
References Hmc58xx::data, Mpu60x0_Spi::data_accel, Hmc58xx::data_available, Mpu60x0_Spi::data_available, Mpu60x0_Spi::data_rates, get_sys_time_usec(), ImuPx4fmu::hmc, hmc58xx_event(), IMU_BOARD_ID, imu_px4fmu, ImuPx4fmu::mpu, mpu60x0_spi_event(), and Mpu60x0_Spi::temp.
void imu_px4fmu_init | ( | void | ) |
Definition at line 63 of file imu_px4fmu.c.
References Mpu60x0Config::accel_range, Mpu60x0_Spi::config, Mpu60x0Config::dlpf_cfg, Mpu60x0Config::gyro_range, ImuPx4fmu::hmc, HMC58XX_ADDR, hmc58xx_init(), IMU_BOARD_ID, imu_px4fmu, imu_set_defaults_accel(), imu_set_defaults_gyro(), ImuPx4fmu::mpu, MPU60X0_ACCEL_SENS_FRAC, MPU60X0_GYRO_SENS_FRAC, mpu60x0_spi_init(), PX4FMU_ACCEL_RANGE, PX4FMU_GYRO_RANGE, Mpu60x0Config::smplrt_div, spi1, and SPI_SLAVE2.
void imu_px4fmu_periodic | ( | void | ) |
Definition at line 82 of file imu_px4fmu.c.
References ImuPx4fmu::hmc, hmc58xx_periodic(), imu_px4fmu, ImuPx4fmu::mpu, and mpu60x0_spi_periodic().
|
extern |
Definition at line 1 of file imu_px4fmu.c.
Referenced by imu_px4fmu_event(), imu_px4fmu_init(), and imu_px4fmu_periodic().