2 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 13 #include <drivers/drv_accel.h> 14 #include <drivers/drv_gyro.h> 15 #include <drivers/drv_hrt.h> 30 if (sensor ==
nullptr) {
47 uint8_t min_depth = (sensor_sample_rate+requested_sample_rate-1)/requested_sample_rate;
49 uint8_t ret = min_depth + (5 * sensor_sample_rate) / 1000;
82 int devid = (ioctl(fd, DEVIOCGDEVICEID, 0) & 0x00FF0000)>>16;
85 ioctl(fd, GYROIOCSLOWPASS, 0);
87 ioctl(fd, GYROIOCSRANGE, 2000);
90 case DRV_GYR_DEVTYPE_MPU6000:
91 case DRV_GYR_DEVTYPE_MPU9250:
93 ioctl(fd, GYROIOCSHWLOWPASS, 256);
95 ioctl(fd, GYROIOCSSAMPLERATE, 1000);
99 case DRV_GYR_DEVTYPE_L3GD20:
101 ioctl(fd, GYROIOCSHWLOWPASS, 100);
103 ioctl(fd, GYROIOCSSAMPLERATE, 800);
111 int samplerate = ioctl(fd, GYROIOCGSAMPLERATE, 0);
112 if (samplerate < 100 || samplerate > 10000) {
121 int devid = (ioctl(fd, DEVIOCGDEVICEID, 0) & 0x00FF0000)>>16;
124 ioctl(fd, ACCELIOCSLOWPASS, 0);
126 ioctl(fd, ACCELIOCSRANGE, 16);
129 case DRV_ACC_DEVTYPE_MPU6000:
130 case DRV_ACC_DEVTYPE_MPU9250:
132 ioctl(fd, ACCELIOCSHWLOWPASS, 256);
134 ioctl(fd, ACCELIOCSSAMPLERATE, 1000);
138 case DRV_ACC_DEVTYPE_LSM303D:
140 ioctl(fd, ACCELIOCSHWLOWPASS, 194);
142 ioctl(fd, ACCELIOCSSAMPLERATE, 1600);
143 ioctl(fd,SENSORIOCSPOLLRATE, 1600);
151 int samplerate = ioctl(fd, ACCELIOCGSAMPLERATE, 0);
152 if (samplerate < 100 || samplerate > 10000) {
196 #ifdef AP_INERTIALSENSOR_PX4_DEBUG 200 _accel_dt_max[i] =
MAX(_accel_dt_max[i],dt);
202 _accel_meas_count[i] ++;
204 if(_accel_meas_count[i] >= 10000) {
207 ::printf(
"a%d %.2f Hz max %.8f s\n", frontend_instance, 10000.0
f/((tnow-_accel_meas_count_start_us[i])*1.0e-6
f),_accel_dt_max[i]);
209 _accel_meas_count_start_us[i] = tnow;
210 _accel_meas_count[i] = 0;
211 _accel_dt_max[i] = 0;
213 #endif // AP_INERTIALSENSOR_PX4_DEBUG 231 #ifdef AP_INERTIALSENSOR_PX4_DEBUG 235 _gyro_dt_max[i] =
MAX(_gyro_dt_max[i],dt);
237 _gyro_meas_count[i] ++;
239 if(_gyro_meas_count[i] >= 10000) {
242 ::printf(
"g%d %.2f Hz max %.8f s\n", frontend_instance, 10000.0
f/((tnow-_gyro_meas_count_start_us[i])*1.0e-6
f), _gyro_dt_max[i]);
244 _gyro_meas_count_start_us[i] = tnow;
245 _gyro_meas_count[i] = 0;
248 #endif // AP_INERTIALSENSOR_PX4_DEBUG 254 struct accel_report accel_report;
255 struct gyro_report gyro_report;
260 while(gyro_valid || accel_valid) {
263 if(gyro_valid && accel_valid && gyro_report.timestamp <= accel_report.timestamp) {
287 ::
read(
_accel_fd[i], &accel_report,
sizeof(accel_report)) ==
sizeof(accel_report) &&
298 ::
read(
_gyro_fd[i], &gyro_report,
sizeof(gyro_report)) ==
sizeof(gyro_report) &&
305 #endif // CONFIG_HAL_BOARD void _set_gyro_error_count(uint8_t instance, uint32_t error_count)
int printf(const char *fmt,...)
Vector3< float > Vector3f
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
uint8_t _gyro_instance[INS_MAX_INSTANCES]
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
void _new_gyro_sample(uint8_t i, gyro_report &gyro_report)
uint8_t _num_gyro_instances
uint64_t _last_accel_timestamp[INS_MAX_INSTANCES]
AP_InertialSensor_PX4(AP_InertialSensor &imu)
void _new_accel_sample(uint8_t i, accel_report &accel_report)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
uint64_t _last_gyro_timestamp[INS_MAX_INSTANCES]
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
uint8_t _accel_instance[INS_MAX_INSTANCES]
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
int _accel_fd[INS_MAX_INSTANCES]
float _accel_sample_time[INS_MAX_INSTANCES]
float _gyro_sample_time[INS_MAX_INSTANCES]
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)
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
void _set_accel_error_count(uint8_t instance, uint32_t error_count)
uint16_t get_sample_rate_hz(void) const
void _publish_temperature(uint8_t instance, float temperature)
void update_gyro(uint8_t instance)
bool _get_gyro_sample(uint8_t i, struct gyro_report &gyro_report)
uint8_t _queue_depth(uint16_t sensor_sample_rate) const
bool _get_accel_sample(uint8_t i, struct accel_report &accel_report)
uint8_t _num_accel_instances
void panic(const char *errormsg,...) FMT_PRINTF(1
#define INS_MAX_INSTANCES
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
void update_accel(uint8_t instance)
int _gyro_fd[INS_MAX_INSTANCES]