diff --git a/src/drivers/imu/bmi055/BMI055.hpp b/src/drivers/imu/bmi055/BMI055.hpp index d8ea4c009ee5..1586c5d769db 100644 --- a/src/drivers/imu/bmi055/BMI055.hpp +++ b/src/drivers/imu/bmi055/BMI055.hpp @@ -60,8 +60,6 @@ class BMI055 : public device::SPI uint8_t _whoami; /** whoami result */ - unsigned _call_interval; - uint8_t _register_wait; uint64_t _reset_wait; diff --git a/src/drivers/imu/bmi055/BMI055_accel.cpp b/src/drivers/imu/bmi055/BMI055_accel.cpp index ae823e7a66d8..028053cec58d 100644 --- a/src/drivers/imu/bmi055/BMI055_accel.cpp +++ b/src/drivers/imu/bmi055/BMI055_accel.cpp @@ -49,34 +49,15 @@ const uint8_t BMI055_accel::_checked_registers[BMI055_ACCEL_NUM_CHECKED_REGISTER BMI055_accel::BMI055_accel(int bus, const char *path_accel, uint32_t device, enum Rotation rotation) : BMI055("BMI055_ACCEL", path_accel, bus, device, SPIDEV_MODE3, BMI055_BUS_SPEED, rotation), ScheduledWorkItem(px4::device_bus_to_wq(get_device_id())), + _px4_accel(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation), _sample_perf(perf_alloc(PC_ELAPSED, "bmi055_accel_read")), _measure_interval(perf_alloc(PC_INTERVAL, "bmi055_accel_measure_interval")), _bad_transfers(perf_alloc(PC_COUNT, "bmi055_accel_bad_transfers")), _bad_registers(perf_alloc(PC_COUNT, "bmi055_accel_bad_registers")), _duplicates(perf_alloc(PC_COUNT, "bmi055_accel_duplicates")), - _accel_reports(nullptr), - _accel_scale{}, - _accel_range_scale(0.0f), - _accel_range_m_s2(0.0f), - _accel_topic(nullptr), - _accel_orb_class_instance(-1), - _accel_class_instance(-1), - _accel_filter_x(BMI055_ACCEL_DEFAULT_RATE, BMI055_ACCEL_DEFAULT_DRIVER_FILTER_FREQ), - _accel_filter_y(BMI055_ACCEL_DEFAULT_RATE, BMI055_ACCEL_DEFAULT_DRIVER_FILTER_FREQ), - _accel_filter_z(BMI055_ACCEL_DEFAULT_RATE, BMI055_ACCEL_DEFAULT_DRIVER_FILTER_FREQ), - _accel_int(1000000 / BMI055_ACCEL_MAX_PUBLISH_RATE), - _last_temperature(0), _got_duplicate(false) { - _device_id.devid_s.devtype = DRV_ACC_DEVTYPE_BMI055; - - // default accel scale factors - _accel_scale.x_offset = 0; - _accel_scale.x_scale = 1.0f; - _accel_scale.y_offset = 0; - _accel_scale.y_scale = 1.0f; - _accel_scale.z_offset = 0; - _accel_scale.z_scale = 1.0f; + _px4_accel.set_device_type(DRV_ACC_DEVTYPE_BMI055); } BMI055_accel::~BMI055_accel() @@ -84,15 +65,6 @@ BMI055_accel::~BMI055_accel() /* make sure we are truly inactive */ stop(); - /* free any existing reports */ - if (_accel_reports != nullptr) { - delete _accel_reports; - } - - if (_accel_class_instance != -1) { - unregister_class_devname(ACCEL_BASE_DEVICE_PATH, _accel_class_instance); - } - /* delete the perf counter */ perf_free(_sample_perf); perf_free(_measure_interval); @@ -113,59 +85,12 @@ BMI055_accel::init() return ret; } - /* allocate basic report buffers */ - _accel_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_accel_s)); - - if (_accel_reports == nullptr) { - return -ENOMEM; - } - - ret = reset(); - - if (ret != OK) { - return ret; - } - - /* Initialize offsets and scales */ - _accel_scale.x_offset = 0; - _accel_scale.x_scale = 1.0f; - _accel_scale.y_offset = 0; - _accel_scale.y_scale = 1.0f; - _accel_scale.z_offset = 0; - _accel_scale.z_scale = 1.0f; - - _accel_class_instance = register_class_devname(ACCEL_BASE_DEVICE_PATH); - - param_t accel_cut_ph = param_find("IMU_ACCEL_CUTOFF"); - float accel_cut = BMI055_ACCEL_DEFAULT_DRIVER_FILTER_FREQ; - - if (accel_cut_ph != PARAM_INVALID && (param_get(accel_cut_ph, &accel_cut) == PX4_OK)) { - - _accel_filter_x.set_cutoff_frequency(BMI055_ACCEL_DEFAULT_RATE, accel_cut); - _accel_filter_y.set_cutoff_frequency(BMI055_ACCEL_DEFAULT_RATE, accel_cut); - _accel_filter_z.set_cutoff_frequency(BMI055_ACCEL_DEFAULT_RATE, accel_cut); - } - - measure(); - - /* advertise sensor topic, measure manually to initialize valid report */ - sensor_accel_s arp; - _accel_reports->get(&arp); - - /* measurement will have generated a report, publish */ - _accel_topic = orb_advertise_multi(ORB_ID(sensor_accel), &arp, - &_accel_orb_class_instance, (external()) ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1); - - if (_accel_topic == nullptr) { - warnx("ADVERT FAIL"); - } - - return ret; + return reset(); } int BMI055_accel::reset() { - write_reg(BMI055_ACC_SOFTRESET, BMI055_SOFT_RESET);//Soft-reset + write_reg(BMI055_ACC_SOFTRESET, BMI055_SOFT_RESET); // Soft-reset up_udelay(5000); write_checked_reg(BMI055_ACC_BW, BMI055_ACCEL_BW_500); //Write accel bandwidth (DLPF) @@ -219,55 +144,6 @@ BMI055_accel::probe() return -EIO; } -ssize_t -BMI055_accel::read(struct file *filp, char *buffer, size_t buflen) -{ - unsigned count = buflen / sizeof(sensor_accel_s); - - /* buffer must be large enough */ - if (count < 1) { - return -ENOSPC; - } - - /* if automatic measurement is not enabled, get a fresh measurement into the buffer */ - if (_call_interval == 0) { - _accel_reports->flush(); - measure(); - } - - /* if no data, error (we could block here) */ - if (_accel_reports->empty()) { - return -EAGAIN; - } - - /* copy reports out of our buffer to the caller */ - sensor_accel_s *arp = reinterpret_cast(buffer); - int transferred = 0; - - while (count--) { - if (!_accel_reports->get(arp)) { - break; - } - - transferred++; - arp++; - } - - /* return the number of bytes transferred */ - return (transferred * sizeof(sensor_accel_s)); -} - -int -BMI055_accel::self_test() -{ - if (perf_event_count(_sample_perf) == 0) { - measure(); - } - - /* return 0 on success, 1 else */ - return (perf_event_count(_sample_perf) > 0) ? 0 : 1; -} - /* deliberately trigger an error in the sensor to trigger recovery */ @@ -279,86 +155,10 @@ BMI055_accel::test_error() print_registers(); } -int -BMI055_accel::ioctl(struct file *filp, int cmd, unsigned long arg) -{ - switch (cmd) { - - case SENSORIOCRESET: - return reset(); - - case SENSORIOCSPOLLRATE: { - switch (arg) { - - /* zero would be bad */ - case 0: - return -EINVAL; - - /* set default polling rate */ - case SENSOR_POLLRATE_DEFAULT: - // Polling at the highest frequency. We may get duplicate values on the sensors - return ioctl(filp, SENSORIOCSPOLLRATE, BMI055_ACCEL_DEFAULT_RATE); - - /* adjust to a legal polling interval in Hz */ - default: { - /* do we need to start internal polling? */ - bool want_start = (_call_interval == 0); - - /* convert hz to hrt interval via microseconds */ - unsigned interval = 1000000 / arg; - - /* check against maximum rate */ - if (interval < 1000) { - return -EINVAL; - } - - // adjust filters - float cutoff_freq_hz = _accel_filter_x.get_cutoff_freq(); - float sample_rate = 1.0e6f / interval; - - _accel_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz); - _accel_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz); - _accel_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz); - - /* update interval for next measurement */ - _call_interval = interval; - - /* if we need to start the poll state machine, do it */ - if (want_start) { - start(); - } - - return OK; - } - } - } - - case ACCELIOCSSCALE: { - /* copy scale, but only if off by a few percent */ - struct accel_calibration_s *s = (struct accel_calibration_s *) arg; - float sum = s->x_scale + s->y_scale + s->z_scale; - - if (sum > 2.0f && sum < 4.0f) { - memcpy(&_accel_scale, s, sizeof(_accel_scale)); - return OK; - - } else { - return -EINVAL; - } - } - - default: - /* give it to the superclass */ - return SPI::ioctl(filp, cmd, arg); - } -} - void BMI055_accel::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits) { - uint8_t val; - - val = read_reg(reg); + uint8_t val = read_reg(reg); val &= ~clearbits; val |= setbits; write_checked_reg(reg, val); @@ -383,29 +183,28 @@ BMI055_accel::set_accel_range(unsigned max_g) uint8_t setbits = 0; uint8_t clearbits = BMI055_ACCEL_RANGE_2_G | BMI055_ACCEL_RANGE_16_G; float lsb_per_g; - float max_accel_g; if (max_g == 0) { max_g = 16; } if (max_g <= 2) { - max_accel_g = 2; + //max_accel_g = 2; setbits |= BMI055_ACCEL_RANGE_2_G; lsb_per_g = 1024; } else if (max_g <= 4) { - max_accel_g = 4; + //max_accel_g = 4; setbits |= BMI055_ACCEL_RANGE_4_G; lsb_per_g = 512; } else if (max_g <= 8) { - max_accel_g = 8; + //max_accel_g = 8; setbits |= BMI055_ACCEL_RANGE_8_G; lsb_per_g = 256; } else if (max_g <= 16) { - max_accel_g = 16; + //max_accel_g = 16; setbits |= BMI055_ACCEL_RANGE_16_G; lsb_per_g = 128; @@ -413,8 +212,7 @@ BMI055_accel::set_accel_range(unsigned max_g) return -EINVAL; } - _accel_range_scale = (CONSTANTS_ONE_G / lsb_per_g); - _accel_range_m_s2 = max_accel_g * CONSTANTS_ONE_G; + _px4_accel.set_scale(CONSTANTS_ONE_G / lsb_per_g); modify_reg(BMI055_ACC_RANGE, clearbits, setbits); @@ -427,13 +225,8 @@ BMI055_accel::start() /* make sure we are stopped first */ stop(); - /* discard any stale data in the buffers */ - _accel_reports->flush(); - /* start polling at the specified rate */ - ScheduleOnInterval(_call_interval - BMI055_TIMER_REDUCTION, 1000); - - reset(); + ScheduleOnInterval(BMI055_ACCEL_DEFAULT_RATE - BMI055_TIMER_REDUCTION, 1000); } void @@ -497,10 +290,6 @@ BMI055_accel::measure() { perf_count(_measure_interval); - uint8_t index = 0, accel_data[8]; - uint16_t lsb, msb, msblsb; - uint8_t status_x, status_y, status_z; - if (hrt_absolute_time() < _reset_wait) { // we're waiting for a reset to complete return; @@ -519,8 +308,12 @@ BMI055_accel::measure() /* * Fetch the full set of measurements from the BMI055 in one pass. */ + uint8_t index = 0; + uint8_t accel_data[8] {}; accel_data[index] = BMI055_ACC_X_L | DIR_READ; + const hrt_abstime timestamp_sample = hrt_absolute_time(); + if (OK != transfer(accel_data, accel_data, sizeof(accel_data))) { return; } @@ -529,20 +322,22 @@ BMI055_accel::measure() /* Extracting accel data from the read data */ index = 1; + uint16_t lsb, msb, msblsb; + lsb = (uint16_t)accel_data[index++]; - status_x = (lsb & BMI055_NEW_DATA_MASK); + uint8_t status_x = (lsb & BMI055_NEW_DATA_MASK); msb = (uint16_t)accel_data[index++]; msblsb = (msb << 8) | lsb; report.accel_x = ((int16_t)msblsb >> 4); /* Data in X axis */ lsb = (uint16_t)accel_data[index++]; - status_y = (lsb & BMI055_NEW_DATA_MASK); + uint8_t status_y = (lsb & BMI055_NEW_DATA_MASK); msb = (uint16_t)accel_data[index++]; msblsb = (msb << 8) | lsb; report.accel_y = ((int16_t)msblsb >> 4); /* Data in Y axis */ lsb = (uint16_t)accel_data[index++]; - status_z = (lsb & BMI055_NEW_DATA_MASK); + uint8_t status_z = (lsb & BMI055_NEW_DATA_MASK); msb = (uint16_t)accel_data[index++]; msblsb = (msb << 8) | lsb; report.accel_z = ((int16_t)msblsb >> 4); /* Data in Z axis */ @@ -582,18 +377,18 @@ BMI055_accel::measure() return; } - /* - * Report buffers. - */ - sensor_accel_s arb; - - arb.timestamp = hrt_absolute_time(); - // report the error count as the sum of the number of bad // transfers and bad register reads. This allows the higher // level code to decide if it should use this sensor based on // whether it has had failures - arb.error_count = perf_event_count(_bad_transfers) + perf_event_count(_bad_registers); + const uint64_t error_count = perf_event_count(_bad_transfers) + perf_event_count(_bad_registers); + _px4_accel.set_error_count(error_count); + + /* + * Temperature is reported as Eight-bit 2’s complement sensor temperature value + * with 0.5 °C/LSB sensitivity and an offset of 23.0 °C + */ + _px4_accel.set_temperature((report.temp * 0.5f) + 23.0f); /* * 1) Scale raw value to SI units using scaling from datasheet. @@ -606,56 +401,7 @@ BMI055_accel::measure() * be subtracted. * */ - - arb.x_raw = report.accel_x; - arb.y_raw = report.accel_y; - arb.z_raw = report.accel_z; - - float xraw_f = report.accel_x; - float yraw_f = report.accel_y; - float zraw_f = report.accel_z; - - // apply user specified rotation - rotate_3f(_rotation, xraw_f, yraw_f, zraw_f); - - float x_in_new = ((xraw_f * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; - float y_in_new = ((yraw_f * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; - float z_in_new = ((zraw_f * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; - - arb.x = _accel_filter_x.apply(x_in_new); - arb.y = _accel_filter_y.apply(y_in_new); - arb.z = _accel_filter_z.apply(z_in_new); - - matrix::Vector3f aval(x_in_new, y_in_new, z_in_new); - matrix::Vector3f aval_integrated; - - bool accel_notify = _accel_int.put(arb.timestamp, aval, aval_integrated, arb.integral_dt); - arb.x_integral = aval_integrated(0); - arb.y_integral = aval_integrated(1); - arb.z_integral = aval_integrated(2); - - arb.scaling = _accel_range_scale; - - /* - * Temperature is reported as Eight-bit 2’s complement sensor temperature value - * with 0.5 °C/LSB sensitivity and an offset of 23.0 °C - */ - _last_temperature = (report.temp * 0.5f) + 23.0f; - arb.temperature = _last_temperature; - - arb.device_id = _device_id.devid; - - _accel_reports->force(&arb); - - /* notify anyone waiting for data */ - if (accel_notify) { - poll_notify(POLLIN); - } - - if (accel_notify && !(_pub_blocked)) { - /* publish it */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb); - } + _px4_accel.update(timestamp_sample, report.accel_x, report.accel_y, report.accel_z); /* stop measuring */ perf_end(_sample_perf); @@ -664,15 +410,12 @@ BMI055_accel::measure() void BMI055_accel::print_info() { - PX4_INFO("Accel"); - perf_print_counter(_sample_perf); perf_print_counter(_measure_interval); perf_print_counter(_bad_transfers); perf_print_counter(_bad_registers); perf_print_counter(_duplicates); - _accel_reports->print_info("accel queue"); ::printf("checked_next: %u\n", _checked_next); for (uint8_t i = 0; i < BMI055_ACCEL_NUM_CHECKED_REGISTERS; i++) { @@ -693,8 +436,7 @@ BMI055_accel::print_info() } } - ::printf("temperature: %.1f\n", (double)_last_temperature); - printf("\n"); + _px4_accel.print_status(); } void diff --git a/src/drivers/imu/bmi055/BMI055_accel.hpp b/src/drivers/imu/bmi055/BMI055_accel.hpp index b82a92923b11..1585ab430fcd 100644 --- a/src/drivers/imu/bmi055/BMI055_accel.hpp +++ b/src/drivers/imu/bmi055/BMI055_accel.hpp @@ -35,14 +35,11 @@ #include "BMI055.hpp" -#include -#include #include -#include #include #include #include -#include +#include #include #include @@ -156,8 +153,8 @@ class BMI055_accel : public BMI055, public px4::ScheduledWorkItem virtual int init(); - virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); - virtual int ioctl(struct file *filp, int cmd, unsigned long arg); + // Start automatic measurement. + void start(); /** * Diagnostics - print some basic information about the driver. @@ -175,28 +172,14 @@ class BMI055_accel : public BMI055, public px4::ScheduledWorkItem private: + PX4Accelerometer _px4_accel; + perf_counter_t _sample_perf; perf_counter_t _measure_interval; perf_counter_t _bad_transfers; perf_counter_t _bad_registers; perf_counter_t _duplicates; - ringbuffer::RingBuffer *_accel_reports; - - struct accel_calibration_s _accel_scale; - float _accel_range_scale; - float _accel_range_m_s2; - - orb_advert_t _accel_topic; - int _accel_orb_class_instance; - int _accel_class_instance; - - math::LowPassFilter2p _accel_filter_x; - math::LowPassFilter2p _accel_filter_y; - math::LowPassFilter2p _accel_filter_z; - - Integrator _accel_int; - // this is used to support runtime checking of key // configuration registers to detect SPI bus errors and sensor // reset @@ -205,16 +188,8 @@ class BMI055_accel : public BMI055, public px4::ScheduledWorkItem uint8_t _checked_values[BMI055_ACCEL_NUM_CHECKED_REGISTERS]; uint8_t _checked_bad[BMI055_ACCEL_NUM_CHECKED_REGISTERS]; - // last temperature reading for print_info() - float _last_temperature; - bool _got_duplicate; - /** - * Start automatic measurement. - */ - void start(); - /** * Stop automatic measurement. */ @@ -261,13 +236,6 @@ class BMI055_accel : public BMI055, public px4::ScheduledWorkItem */ int set_accel_range(unsigned max_g); - /** - * Measurement self test - * - * @return 0 on success, 1 on failure - */ - int self_test(); - /* * check that key registers still have the right value */ diff --git a/src/drivers/imu/bmi055/BMI055_gyro.cpp b/src/drivers/imu/bmi055/BMI055_gyro.cpp index cd6406ce0be0..8d135f890d53 100644 --- a/src/drivers/imu/bmi055/BMI055_gyro.cpp +++ b/src/drivers/imu/bmi055/BMI055_gyro.cpp @@ -50,33 +50,13 @@ const uint8_t BMI055_gyro::_checked_registers[BMI055_GYRO_NUM_CHECKED_REGISTERS] BMI055_gyro::BMI055_gyro(int bus, const char *path_gyro, uint32_t device, enum Rotation rotation) : BMI055("BMI055_GYRO", path_gyro, bus, device, SPIDEV_MODE3, BMI055_BUS_SPEED, rotation), ScheduledWorkItem(px4::device_bus_to_wq(get_device_id())), + _px4_gyro(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation), _sample_perf(perf_alloc(PC_ELAPSED, "bmi055_gyro_read")), _measure_interval(perf_alloc(PC_INTERVAL, "bmi055_gyro_measure_interval")), _bad_transfers(perf_alloc(PC_COUNT, "bmi055_gyro_bad_transfers")), - _bad_registers(perf_alloc(PC_COUNT, "bmi055_gyro_bad_registers")), - _gyro_reports(nullptr), - _gyro_scale{}, - _gyro_range_scale(0.0f), - _gyro_range_rad_s(0.0f), - _gyro_topic(nullptr), - _gyro_orb_class_instance(-1), - _gyro_class_instance(-1), - _gyro_sample_rate(BMI055_GYRO_DEFAULT_RATE), - _gyro_filter_x(BMI055_GYRO_DEFAULT_RATE, BMI055_GYRO_DEFAULT_DRIVER_FILTER_FREQ), - _gyro_filter_y(BMI055_GYRO_DEFAULT_RATE, BMI055_GYRO_DEFAULT_DRIVER_FILTER_FREQ), - _gyro_filter_z(BMI055_GYRO_DEFAULT_RATE, BMI055_GYRO_DEFAULT_DRIVER_FILTER_FREQ), - _gyro_int(1000000 / BMI055_GYRO_MAX_PUBLISH_RATE, true), - _last_temperature(0) + _bad_registers(perf_alloc(PC_COUNT, "bmi055_gyro_bad_registers")) { - _device_id.devid_s.devtype = DRV_GYR_DEVTYPE_BMI055; - - // default gyro scale factors - _gyro_scale.x_offset = 0; - _gyro_scale.x_scale = 1.0f; - _gyro_scale.y_offset = 0; - _gyro_scale.y_scale = 1.0f; - _gyro_scale.z_offset = 0; - _gyro_scale.z_scale = 1.0f; + _px4_gyro.set_device_type(DRV_GYR_DEVTYPE_BMI055); } BMI055_gyro::~BMI055_gyro() @@ -84,15 +64,6 @@ BMI055_gyro::~BMI055_gyro() /* make sure we are truly inactive */ stop(); - /* free any existing reports */ - if (_gyro_reports != nullptr) { - delete _gyro_reports; - } - - if (_gyro_class_instance != -1) { - unregister_class_devname(GYRO_BASE_DEVICE_PATH, _gyro_class_instance); - } - /* delete the perf counter */ perf_free(_sample_perf); perf_free(_measure_interval); @@ -112,53 +83,7 @@ BMI055_gyro::init() return ret; } - /* allocate basic report buffers */ - _gyro_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_gyro_s)); - - if (_gyro_reports == nullptr) { - return -ENOMEM; - } - - ret = reset(); - - if (ret != OK) { - return ret; - } - - /* Initialize offsets and scales */ - _gyro_scale.x_offset = 0; - _gyro_scale.x_scale = 1.0f; - _gyro_scale.y_offset = 0; - _gyro_scale.y_scale = 1.0f; - _gyro_scale.z_offset = 0; - _gyro_scale.z_scale = 1.0f; - - param_t gyro_cut_ph = param_find("IMU_GYRO_CUTOFF"); - float gyro_cut = BMI055_GYRO_DEFAULT_DRIVER_FILTER_FREQ; - - if (gyro_cut_ph != PARAM_INVALID && (param_get(gyro_cut_ph, &gyro_cut) == PX4_OK)) { - - _gyro_filter_x.set_cutoff_frequency(BMI055_GYRO_DEFAULT_RATE, gyro_cut); - _gyro_filter_y.set_cutoff_frequency(BMI055_GYRO_DEFAULT_RATE, gyro_cut); - _gyro_filter_z.set_cutoff_frequency(BMI055_GYRO_DEFAULT_RATE, gyro_cut); - } - - _gyro_class_instance = register_class_devname(GYRO_BASE_DEVICE_PATH); - - measure(); - - /* advertise sensor topic, measure manually to initialize valid report */ - sensor_gyro_s grp; - _gyro_reports->get(&grp); - - _gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp, - &_gyro_orb_class_instance, (external()) ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1); - - if (_gyro_topic == nullptr) { - warnx("ADVERT FAIL"); - } - - return ret; + return reset(); } int BMI055_gyro::reset() @@ -225,19 +150,19 @@ BMI055_gyro::gyro_set_sample_rate(float frequency) if (frequency <= 100) { setbits |= BMI055_GYRO_RATE_100; /* 32 Hz cutoff */ - _gyro_sample_rate = 100; + //_gyro_sample_rate = 100; } else if (frequency <= 250) { setbits |= BMI055_GYRO_RATE_400; /* 47 Hz cutoff */ - _gyro_sample_rate = 400; + //_gyro_sample_rate = 400; } else if (frequency <= 1000) { setbits |= BMI055_GYRO_RATE_1000; /* 116 Hz cutoff */ - _gyro_sample_rate = 1000; + //_gyro_sample_rate = 1000; } else if (frequency > 1000) { setbits |= BMI055_GYRO_RATE_2000; /* 230 Hz cutoff */ - _gyro_sample_rate = 2000; + //_gyro_sample_rate = 2000; } else { return -EINVAL; @@ -248,17 +173,6 @@ BMI055_gyro::gyro_set_sample_rate(float frequency) return OK; } -int -BMI055_gyro::self_test() -{ - if (perf_event_count(_sample_perf) == 0) { - measure(); - } - - /* return 0 on success, 1 else */ - return (perf_event_count(_sample_perf) > 0) ? 0 : 1; -} - /* deliberately trigger an error in the sensor to trigger recovery */ @@ -270,113 +184,10 @@ BMI055_gyro::test_error() print_registers(); } -ssize_t -BMI055_gyro::read(struct file *filp, char *buffer, size_t buflen) -{ - unsigned count = buflen / sizeof(sensor_gyro_s); - - /* buffer must be large enough */ - if (count < 1) { - return -ENOSPC; - } - - /* if automatic measurement is not enabled, get a fresh measurement into the buffer */ - if (_call_interval == 0) { - _gyro_reports->flush(); - measure(); - } - - /* if no data, error (we could block here) */ - if (_gyro_reports->empty()) { - return -EAGAIN; - } - - /* copy reports out of our buffer to the caller */ - sensor_gyro_s *grp = reinterpret_cast(buffer); - int transferred = 0; - - while (count--) { - if (!_gyro_reports->get(grp)) { - break; - } - - transferred++; - grp++; - } - - /* return the number of bytes transferred */ - return (transferred * sizeof(sensor_gyro_s)); -} - -int -BMI055_gyro::ioctl(struct file *filp, int cmd, unsigned long arg) -{ - switch (cmd) { - - case SENSORIOCRESET: - return reset(); - - case SENSORIOCSPOLLRATE: { - switch (arg) { - - /* zero would be bad */ - case 0: - return -EINVAL; - - /* set default polling rate */ - case SENSOR_POLLRATE_DEFAULT: - return ioctl(filp, SENSORIOCSPOLLRATE, BMI055_GYRO_DEFAULT_RATE); - - /* adjust to a legal polling interval in Hz */ - default: { - /* do we need to start internal polling? */ - bool want_start = (_call_interval == 0); - - /* convert hz to hrt interval via microseconds */ - unsigned interval = 1000000 / arg; - - /* check against maximum rate */ - if (interval < 1000) { - return -EINVAL; - } - - // adjust filters - float cutoff_freq_hz_gyro = _gyro_filter_x.get_cutoff_freq(); - float sample_rate = 1.0e6f / interval; - _gyro_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro); - _gyro_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro); - _gyro_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro); - - /* update interval for next measurement */ - _call_interval = interval; - - /* if we need to start the poll state machine, do it */ - if (want_start) { - start(); - } - - return OK; - } - } - } - - case GYROIOCSSCALE: - /* copy scale in */ - memcpy(&_gyro_scale, (struct gyro_calibration_s *) arg, sizeof(_gyro_scale)); - return OK; - - default: - /* give it to the superclass */ - return SPI::ioctl(filp, cmd, arg); - } -} - void BMI055_gyro::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits) { - uint8_t val; - - val = read_reg(reg); + uint8_t val = read_reg(reg); val &= ~clearbits; val |= setbits; write_checked_reg(reg, val); @@ -401,34 +212,33 @@ BMI055_gyro::set_gyro_range(unsigned max_dps) uint8_t setbits = 0; uint8_t clearbits = BMI055_GYRO_RANGE_125_DPS | BMI055_GYRO_RANGE_250_DPS; float lsb_per_dps; - float max_gyro_dps; if (max_dps == 0) { max_dps = 2000; } if (max_dps <= 125) { - max_gyro_dps = 125; + //max_gyro_dps = 125; lsb_per_dps = 262.4; setbits |= BMI055_GYRO_RANGE_125_DPS; } else if (max_dps <= 250) { - max_gyro_dps = 250; + //max_gyro_dps = 250; lsb_per_dps = 131.2; setbits |= BMI055_GYRO_RANGE_250_DPS; } else if (max_dps <= 500) { - max_gyro_dps = 500; + //max_gyro_dps = 500; lsb_per_dps = 65.6; setbits |= BMI055_GYRO_RANGE_500_DPS; } else if (max_dps <= 1000) { - max_gyro_dps = 1000; + //max_gyro_dps = 1000; lsb_per_dps = 32.8; setbits |= BMI055_GYRO_RANGE_1000_DPS; } else if (max_dps <= 2000) { - max_gyro_dps = 2000; + //max_gyro_dps = 2000; lsb_per_dps = 16.4; setbits |= BMI055_GYRO_RANGE_2000_DPS; @@ -436,8 +246,7 @@ BMI055_gyro::set_gyro_range(unsigned max_dps) return -EINVAL; } - _gyro_range_rad_s = (max_gyro_dps / 180.0f * M_PI_F); - _gyro_range_scale = (M_PI_F / (180.0f * lsb_per_dps)); + _px4_gyro.set_scale(M_PI_F / (180.0f * lsb_per_dps)); modify_reg(BMI055_GYR_RANGE, clearbits, setbits); @@ -450,13 +259,8 @@ BMI055_gyro::start() /* make sure we are stopped first */ stop(); - /* discard any stale data in the buffers */ - _gyro_reports->flush(); - /* start polling at the specified rate */ - ScheduleOnInterval(_call_interval - BMI055_TIMER_REDUCTION, 1000); - - reset(); + ScheduleOnInterval(BMI055_GYRO_DEFAULT_RATE - BMI055_TIMER_REDUCTION, 1000); } void @@ -542,6 +346,7 @@ BMI055_gyro::measure() */ bmi_gyroreport.cmd = BMI055_GYR_X_L | DIR_READ; + const hrt_abstime timestamp_sample = hrt_absolute_time(); if (OK != transfer((uint8_t *)&bmi_gyroreport, ((uint8_t *)&bmi_gyroreport), sizeof(bmi_gyroreport))) { return; @@ -577,18 +382,18 @@ BMI055_gyro::measure() return; } - /* - * Report buffers. - */ - sensor_gyro_s grb; - - grb.timestamp = hrt_absolute_time(); - // report the error count as the sum of the number of bad // transfers and bad register reads. This allows the higher // level code to decide if it should use this sensor based on // whether it has had failures - grb.error_count = perf_event_count(_bad_transfers) + perf_event_count(_bad_registers); + const uint64_t error_count = perf_event_count(_bad_transfers) + perf_event_count(_bad_registers); + _px4_gyro.set_error_count(error_count); + + /* + * Temperature is reported as Eight-bit 2’s complement sensor temperature value + * with 0.5 °C/LSB sensitivity and an offset of 23.0 °C + */ + _px4_gyro.set_temperature((report.temp * 0.5f) + 23.0f); /* * 1) Scale raw value to SI units using scaling from datasheet. @@ -604,56 +409,7 @@ BMI055_gyro::measure() * the offset is 74 from the origin and subtracting * 74 from all measurements centers them around zero. */ - - grb.x_raw = report.gyro_x; - grb.y_raw = report.gyro_y; - grb.z_raw = report.gyro_z; - - float xraw_f = report.gyro_x; - float yraw_f = report.gyro_y; - float zraw_f = report.gyro_z; - - // apply user specified rotation - rotate_3f(_rotation, xraw_f, yraw_f, zraw_f); - - float x_gyro_in_new = ((xraw_f * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; - float y_gyro_in_new = ((yraw_f * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; - float z_gyro_in_new = ((zraw_f * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; - - grb.x = _gyro_filter_x.apply(x_gyro_in_new); - grb.y = _gyro_filter_y.apply(y_gyro_in_new); - grb.z = _gyro_filter_z.apply(z_gyro_in_new); - - matrix::Vector3f gval(x_gyro_in_new, y_gyro_in_new, z_gyro_in_new); - matrix::Vector3f gval_integrated; - - bool gyro_notify = _gyro_int.put(grb.timestamp, gval, gval_integrated, grb.integral_dt); - grb.x_integral = gval_integrated(0); - grb.y_integral = gval_integrated(1); - grb.z_integral = gval_integrated(2); - - grb.scaling = _gyro_range_scale; - - /* - * Temperature is reported as Eight-bit 2’s complement sensor temperature value - * with 0.5 °C/LSB sensitivity and an offset of 23.0 °C - */ - _last_temperature = (report.temp * 0.5f) + 23.0f; - grb.temperature = _last_temperature; - - grb.device_id = _device_id.devid; - - _gyro_reports->force(&grb); - - /* notify anyone waiting for data */ - if (gyro_notify) { - poll_notify(POLLIN); - } - - if (gyro_notify && !(_pub_blocked)) { - /* publish it */ - orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &grb); - } + _px4_gyro.update(timestamp_sample, report.gyro_x, report.gyro_y, report.gyro_z); /* stop measuring */ perf_end(_sample_perf); @@ -669,7 +425,6 @@ BMI055_gyro::print_info() perf_print_counter(_bad_transfers); perf_print_counter(_bad_registers); - _gyro_reports->print_info("gyro queue"); ::printf("checked_next: %u\n", _checked_next); for (uint8_t i = 0; i < BMI055_GYRO_NUM_CHECKED_REGISTERS; i++) { @@ -690,8 +445,7 @@ BMI055_gyro::print_info() } } - ::printf("temperature: %.1f\n", (double)_last_temperature); - printf("\n"); + _px4_gyro.print_status(); } void diff --git a/src/drivers/imu/bmi055/BMI055_gyro.hpp b/src/drivers/imu/bmi055/BMI055_gyro.hpp index 458e54202ffb..608628575017 100644 --- a/src/drivers/imu/bmi055/BMI055_gyro.hpp +++ b/src/drivers/imu/bmi055/BMI055_gyro.hpp @@ -35,14 +35,11 @@ #include "BMI055.hpp" -#include -#include #include -#include #include #include #include -#include +#include #include #include @@ -148,8 +145,8 @@ class BMI055_gyro : public BMI055, public px4::ScheduledWorkItem virtual int init(); - virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); - virtual int ioctl(struct file *filp, int cmd, unsigned long arg); + // Start automatic measurement. + void start(); /** * Diagnostics - print some basic information about the driver. @@ -167,29 +164,13 @@ class BMI055_gyro : public BMI055, public px4::ScheduledWorkItem private: + PX4Gyroscope _px4_gyro; + perf_counter_t _sample_perf; perf_counter_t _measure_interval; perf_counter_t _bad_transfers; perf_counter_t _bad_registers; - ringbuffer::RingBuffer *_gyro_reports; - - struct gyro_calibration_s _gyro_scale; - float _gyro_range_scale; - float _gyro_range_rad_s; - - orb_advert_t _gyro_topic; - int _gyro_orb_class_instance; - int _gyro_class_instance; - - float _gyro_sample_rate; - - math::LowPassFilter2p _gyro_filter_x; - math::LowPassFilter2p _gyro_filter_y; - math::LowPassFilter2p _gyro_filter_z; - - Integrator _gyro_int; - // this is used to support runtime checking of key // configuration registers to detect SPI bus errors and sensor // reset @@ -198,14 +179,6 @@ class BMI055_gyro : public BMI055, public px4::ScheduledWorkItem uint8_t _checked_values[BMI055_GYRO_NUM_CHECKED_REGISTERS]; uint8_t _checked_bad[BMI055_GYRO_NUM_CHECKED_REGISTERS]; - // last temperature reading for print_info() - float _last_temperature; - - /** - * Start automatic measurement. - */ - void start(); - /** * Stop automatic measurement. */ @@ -252,13 +225,6 @@ class BMI055_gyro : public BMI055, public px4::ScheduledWorkItem */ int set_gyro_range(unsigned max_dps); - /** - * Measurement self test - * - * @return 0 on success, 1 on failure - */ - int self_test(); - /* * set gyro sample rate */ diff --git a/src/drivers/imu/bmi055/bmi055_main.cpp b/src/drivers/imu/bmi055/bmi055_main.cpp index cd9320b02f53..c828a13beeac 100644 --- a/src/drivers/imu/bmi055/bmi055_main.cpp +++ b/src/drivers/imu/bmi055/bmi055_main.cpp @@ -56,8 +56,6 @@ BMI055_gyro *g_gyr_dev_ext; // on external bus (gyro) void start(bool, enum Rotation, enum sensor_type); void stop(bool, enum sensor_type); -void test(bool, enum sensor_type); -void reset(bool, enum sensor_type); void info(bool, enum sensor_type); void regdump(bool, enum sensor_type); void testerror(bool, enum sensor_type); @@ -72,10 +70,9 @@ void usage(); void start(bool external_bus, enum Rotation rotation, enum sensor_type sensor) { - - int fd_acc, fd_gyr; BMI055_accel **g_dev_acc_ptr = external_bus ? &g_acc_dev_ext : &g_acc_dev_int; const char *path_accel = external_bus ? BMI055_DEVICE_PATH_ACCEL_EXT : BMI055_DEVICE_PATH_ACCEL; + BMI055_gyro **g_dev_gyr_ptr = external_bus ? &g_gyr_dev_ext : &g_gyr_dev_int; const char *path_gyro = external_bus ? BMI055_DEVICE_PATH_GYRO_EXT : BMI055_DEVICE_PATH_GYRO; @@ -106,18 +103,8 @@ start(bool external_bus, enum Rotation rotation, enum sensor_type sensor) goto fail_accel; } - /* set the poll rate to default, starts automatic data collection */ - fd_acc = open(path_accel, O_RDONLY); - - if (fd_acc < 0) { - goto fail_accel; - } - - if (ioctl(fd_acc, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { - goto fail_accel; - } - - close(fd_acc); + // start automatic data collection + (*g_dev_acc_ptr)->start(); } if (sensor == BMI055_GYRO) { @@ -146,18 +133,8 @@ start(bool external_bus, enum Rotation rotation, enum sensor_type sensor) goto fail_gyro; } - /* set the poll rate to default, starts automatic data collection */ - fd_gyr = open(path_gyro, O_RDONLY); - - if (fd_gyr < 0) { - goto fail_gyro; - } - - if (ioctl(fd_gyr, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { - goto fail_gyro; - } - - close(fd_gyr); + // start automatic data collection + (*g_dev_gyr_ptr)->start(); } exit(PX4_OK); @@ -215,131 +192,6 @@ stop(bool external_bus, enum sensor_type sensor) } -/** - * Perform some basic functional tests on the driver; - * make sure we can collect data from the sensor in polled - * and automatic modes. - */ -void -test(bool external_bus, enum sensor_type sensor) -{ - const char *path_accel = external_bus ? BMI055_DEVICE_PATH_ACCEL_EXT : BMI055_DEVICE_PATH_ACCEL; - const char *path_gyro = external_bus ? BMI055_DEVICE_PATH_GYRO_EXT : BMI055_DEVICE_PATH_GYRO; - sensor_accel_s a_report{}; - sensor_gyro_s g_report{}; - ssize_t sz; - - if (sensor == BMI055_ACCEL) { - /* get the accel driver */ - int fd_acc = open(path_accel, O_RDONLY); - - if (fd_acc < 0) { - err(1, "%s Accel file open failed (try 'bmi055 -A start')", - path_accel); - } - - /* do a simple demand read */ - sz = read(fd_acc, &a_report, sizeof(a_report)); - - if (sz != sizeof(a_report)) { - warnx("ret: %d, expected: %d", sz, sizeof(a_report)); - err(1, "immediate accel read failed"); - } - - print_message(a_report); - - /* reset to default polling */ - if (ioctl(fd_acc, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { - err(1, "accel reset to default polling"); - } - - close(fd_acc); - } - - if (sensor == BMI055_GYRO) { - - /* get the gyro driver */ - int fd_gyr = open(path_gyro, O_RDONLY); - - if (fd_gyr < 0) { - err(1, "%s Gyro file open failed (try 'bmi055 -G start')", path_gyro); - } - - /* do a simple demand read */ - sz = read(fd_gyr, &g_report, sizeof(g_report)); - - if (sz != sizeof(g_report)) { - warnx("ret: %d, expected: %d", sz, sizeof(g_report)); - err(1, "immediate gyro read failed"); - } - - print_message(g_report); - - /* reset to default polling */ - if (ioctl(fd_gyr, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { - err(1, "gyro reset to default polling"); - } - - close(fd_gyr); - } - - if ((sensor == BMI055_ACCEL) || (sensor == BMI055_GYRO)) { - /* XXX add poll-rate tests here too */ - reset(external_bus, sensor); - } - - errx(0, "PASS"); -} - -/** - * Reset the driver. - */ -void -reset(bool external_bus, enum sensor_type sensor) -{ - const char *path_accel = external_bus ? BMI055_DEVICE_PATH_ACCEL_EXT : BMI055_DEVICE_PATH_ACCEL; - const char *path_gyro = external_bus ? BMI055_DEVICE_PATH_GYRO_EXT : BMI055_DEVICE_PATH_GYRO; - - if (sensor == BMI055_ACCEL) { - int fd_acc = open(path_accel, O_RDONLY); - - if (fd_acc < 0) { - err(1, "Opening accel file failed "); - } - - if (ioctl(fd_acc, SENSORIOCRESET, 0) < 0) { - err(1, "accel driver reset failed"); - } - - - if (ioctl(fd_acc, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { - err(1, "accel driver poll restart failed"); - } - - close(fd_acc); - } - - if (sensor == BMI055_GYRO) { - int fd_gyr = open(path_gyro, O_RDONLY); - - if (fd_gyr < 0) { - err(1, "Opening gyro file failed "); - } - - if (ioctl(fd_gyr, SENSORIOCRESET, 0) < 0) { - err(1, "gyro driver reset failed"); - } - - if (ioctl(fd_gyr, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { - err(1, "gyro driver poll restart failed"); - } - - close(fd_gyr); - } - - exit(0); -} - /** * Print a little info about the driver. */ @@ -431,7 +283,7 @@ testerror(bool external_bus, enum sensor_type sensor) void usage() { - warnx("missing command: try 'start', 'info', 'test', 'stop',\n'reset', 'regdump', 'testerror'"); + warnx("missing command: try 'start', 'info', 'stop', 'regdump', 'testerror'"); warnx("options:"); warnx(" -X (external bus)"); warnx(" -R rotation"); @@ -446,7 +298,6 @@ BMI055::BMI055(const char *name, const char *devname, int bus, uint32_t device, uint32_t frequency, enum Rotation rotation): SPI(name, devname, bus, device, mode, frequency), _whoami(0), - _call_interval(0), _register_wait(0), _reset_wait(0), _rotation(rotation), @@ -541,20 +392,6 @@ bmi055_main(int argc, char *argv[]) bmi055::stop(external_bus, sensor); } - /* - * Test the driver/device. - */ - if (!strcmp(verb, "test")) { - bmi055::test(external_bus, sensor); - } - - /* - * Reset the driver. - */ - if (!strcmp(verb, "reset")) { - bmi055::reset(external_bus, sensor); - } - /* * Print driver information. */