Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

move IMU integration to sensors/vehicle_imu to fix potential accel/gyro sync issues #14906

Merged
merged 28 commits into from
May 30, 2020
Merged
Show file tree
Hide file tree
Changes from 7 commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
2906f40
sensors/vehicle_imu: integrate accel and gyro
dagar May 9, 2020
9ba72f7
lockstep testing hacks
dagar May 19, 2020
792b157
Merge remote-tracking branch 'px4/master' into pr-sensors_vehicle_imu…
dagar May 20, 2020
3bef9c3
changes from code review
dagar May 20, 2020
eeecdc5
Integrator move from lib/drivers/device -> sensors/vehicle_imu
dagar May 20, 2020
859b1eb
advertise vehicle_imu_status immediately
dagar May 20, 2020
b3f8ed7
Merge remote-tracking branch 'px4/master' into pr-sensors_vehicle_imu…
dagar May 23, 2020
3cc350d
Merge remote-tracking branch 'px4/master' into pr-sensors_vehicle_imu…
dagar May 25, 2020
f645b3b
sensors: create VehicleIMU instances sequentially as data is actually…
dagar May 25, 2020
ff27251
new icm20948 remove obsolete PX4Accelerometer/PX4Gyroscope set_update…
dagar May 25, 2020
a1be128
Merge remote-tracking branch 'px4/master' into pr-sensors_vehicle_imu…
dagar May 26, 2020
c4b6c72
sensors/vehicle_imu: integrate gyro first, then only take accel until…
dagar May 26, 2020
d20e341
sensors/vehicle_imu: remove debug perf counters
dagar May 27, 2020
09b3dab
Update src/modules/sensors/vehicle_imu/VehicleIMU.cpp
dagar May 27, 2020
680de1a
Merge remote-tracking branch 'px4/master' into pr-sensors_vehicle_imu…
dagar May 27, 2020
e0180f3
sensors/vehicle_imu: don't integrate every available gyro sample unle…
dagar May 27, 2020
470f418
TESTING
dagar May 28, 2020
5f07340
Merge remote-tracking branch 'px4/master' into pr-sensors_vehicle_imu…
dagar May 28, 2020
8c0a3d6
logger: limit vehicle_imu
dagar May 28, 2020
ba2fd75
vehicle_imu error counts
dagar May 28, 2020
9c0f8c5
fix typo and formatting
dagar May 28, 2020
ebee09b
fix sensor_selection publication and add backup schedules
dagar May 28, 2020
ec5a35f
ekf2: remove accel/gyro bias reset warning (too noisy)
dagar May 28, 2020
1b2769e
sensors status cleanup whitespace and ordering
dagar May 28, 2020
44ec4ea
IMU_INTEG_RATE add enums and comment
dagar May 28, 2020
043f83a
sensors status minor tweaks
dagar May 28, 2020
90c1864
remove IMU_INTEG_RATE enums
dagar May 28, 2020
e463c7e
Merge remote-tracking branch 'px4/master' into pr-sensors_vehicle_imu…
dagar May 30, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 2 additions & 8 deletions .ci/Jenkinsfile-hardware
Original file line number Diff line number Diff line change
Expand Up @@ -770,19 +770,16 @@ void statusFTDI() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener logger_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel_fifo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel_integrated"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_baro"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_combined"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_gyro"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_gyro_fifo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_gyro_integrated"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_gyro_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_mag"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener servorail_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener system_power"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_attitude"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_imu"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_imu_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener vehicle_local_position"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "logger status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /"'
Expand Down Expand Up @@ -832,19 +829,16 @@ void statusSEGGER() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener logger_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel_fifo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel_integrated"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_baro"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_combined"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_gyro"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_gyro_fifo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_gyro_integrated"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_gyro_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_mag"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener servorail_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener system_power"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_attitude"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_imu"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_imu_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener vehicle_local_position"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "logger status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /"'
Expand Down
4 changes: 2 additions & 2 deletions ROMFS/px4fmu_common/init.d-posix/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -123,8 +123,8 @@ then
param set CAL_ACC0_ID 1311244
param set CAL_ACC_PRIME 1311244

param set CAL_GYRO0_ID 2294028
param set CAL_GYRO_PRIME 2294028
param set CAL_GYRO0_ID 1311244
param set CAL_GYRO_PRIME 1311244

param set CAL_MAG0_ID 197388
param set CAL_MAG_PRIME 197388
Expand Down
5 changes: 1 addition & 4 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -112,15 +112,11 @@ set(msg_files
satellite_info.msg
sensor_accel.msg
sensor_accel_fifo.msg
sensor_accel_integrated.msg
sensor_accel_status.msg
sensor_baro.msg
sensor_combined.msg
sensor_correction.msg
sensor_gyro.msg
sensor_gyro_fifo.msg
sensor_gyro_integrated.msg
sensor_gyro_status.msg
sensor_mag.msg
sensor_preflight.msg
sensor_selection.msg
Expand Down Expand Up @@ -154,6 +150,7 @@ set(msg_files
vehicle_global_position.msg
vehicle_gps_position.msg
vehicle_imu.msg
vehicle_imu_status.msg
vehicle_land_detected.msg
vehicle_local_position.msg
vehicle_local_position_setpoint.msg
Expand Down
6 changes: 5 additions & 1 deletion msg/sensor_accel.msg
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,8 @@ float32 z # acceleration in the NED Z board axis in m/s^2

float32 temperature # temperature in degrees celsius

uint8 ORB_QUEUE_LENGTH = 4
uint32 error_count

uint8[3] clip_counter # clip count per axis in the sample period

uint8 ORB_QUEUE_LENGTH = 8
12 changes: 0 additions & 12 deletions msg/sensor_accel_integrated.msg

This file was deleted.

17 changes: 0 additions & 17 deletions msg/sensor_accel_status.msg

This file was deleted.

4 changes: 3 additions & 1 deletion msg/sensor_gyro.msg
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,6 @@ float32 z # angular velocity in the NED Z board axis in rad/s

float32 temperature # temperature in degrees celsius

uint8 ORB_QUEUE_LENGTH = 4
uint32 error_count

uint8 ORB_QUEUE_LENGTH = 8
12 changes: 0 additions & 12 deletions msg/sensor_gyro_integrated.msg

This file was deleted.

19 changes: 0 additions & 19 deletions msg/sensor_gyro_status.msg

This file was deleted.

12 changes: 12 additions & 0 deletions msg/tools/px_generate_uorb_topic_helper.py
Original file line number Diff line number Diff line change
Expand Up @@ -305,6 +305,18 @@ def print_field(field):
print("char device_id_buffer[80];")
print("device::Device::device_id_print_buffer(device_id_buffer, sizeof(device_id_buffer), message.device_id);")
print("PX4_INFO_RAW(\"\\tdevice_id: %d (%s) \\n\", message.device_id, device_id_buffer);")
elif field.name == 'accel_device_id':
print("char accel_device_id_buffer[80];")
print("device::Device::device_id_print_buffer(accel_device_id_buffer, sizeof(accel_device_id_buffer), message.accel_device_id);")
print("PX4_INFO_RAW(\"\\taccel_device_id: %d (%s) \\n\", message.accel_device_id, accel_device_id_buffer);")
elif field.name == 'gyro_device_id':
print("char gyro_device_id_buffer[80];")
print("device::Device::device_id_print_buffer(gyro_device_id_buffer, sizeof(gyro_device_id_buffer), message.gyro_device_id);")
print("PX4_INFO_RAW(\"\\tgyro_device_id: %d (%s) \\n\", message.gyro_device_id, gyro_device_id_buffer);")
elif field.name == 'baro_device_id':
print("char baro_device_id_buffer[80];")
print("device::Device::device_id_print_buffer(baro_device_id_buffer, sizeof(baro_device_id_buffer), message.baro_device_id);")
print("PX4_INFO_RAW(\"\\tbaro_device_id: %d (%s) \\n\", message.baro_device_id, baro_device_id_buffer);")
elif is_array and 'char' in field.type:
print(("PX4_INFO_RAW(\"\\t" + field.name + ": \\\"%." + str(array_length) + "s\\\" \\n\", message." + field.name + ");"))
else:
Expand Down
34 changes: 14 additions & 20 deletions msg/tools/uorb_rtps_message_ids.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -267,40 +267,34 @@ rtps:
id: 117
- msg: sensor_accel_fifo
id: 118
- msg: sensor_accel_status
id: 119
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@dagar can you rearrange the ID's so we don't have unused numbers? Thanks!

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shift the entire set after 118 down? What's the expectation/requirement for these id numbers (persistence, etc)?

- msg: sensor_gyro_fifo
id: 119
- msg: vehicle_imu
id: 120
- msg: sensor_gyro_status
- msg: vehicle_imu_status
id: 121
- msg: sensor_accel_integrated
id: 122
- msg: sensor_gyro_integrated
id: 123
- msg: vehicle_imu
id: 124
- msg: vehicle_angular_acceleration
id: 125
id: 122
- msg: logger_status
id: 126
id: 123
- msg: rpm
id: 127
id: 124
- msg: hover_thrust_estimate
id: 128
id: 125
- msg: trajectory_bezier
id: 129
id: 126
- msg: vehicle_trajectory_bezier
id: 130
id: 127
- msg: timesync_status
id: 131
id: 128
- msg: orb_test
id: 132
id: 129
- msg: orb_test_medium
id: 133
id: 130
- msg: orb_test_large
id: 134
id: 131
- msg: yaw_estimator_status
id: 135
id: 132
########## multi topics: begin ##########
- msg: actuator_controls_0
id: 150
Expand Down
4 changes: 2 additions & 2 deletions msg/vehicle_imu.msg
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@ uint32 gyro_device_id # Gyroscope unique device ID for the sensor that

float32[3] delta_angle # delta angle in the NED board axis in rad/s over the integration time frame (dt)
float32[3] delta_velocity # delta velocity in the NED board axis in m/s over the integration time frame (dt)

uint16 dt # integration period in us
uint16 delta_angle_dt # integration period in us
uint16 delta_velocity_dt # integration period in us

uint8 CLIPPING_X = 1
uint8 CLIPPING_Y = 2
Expand Down
16 changes: 16 additions & 0 deletions msg/vehicle_imu_status.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
uint64 timestamp # time since system start (microseconds)

uint32 accel_device_id # unique device ID for the sensor that does not change between power cycles
uint32 gyro_device_id # unique device ID for the sensor that does not change between power cycles

uint32[3] accel_clipping # clipping per axis

uint32 accel_error_count
uint32 gyro_error_count

uint16 accel_rate_hz
uint16 gyro_rate_hz

float32 accel_vibration_metric # high frequency vibration level in the IMU delta velocity data (m/s)
float32 gyro_vibration_metric # high frequency vibration level in the IMU delta velocity data (m/s)
float32 gyro_coning_vibration # Level of coning vibration in the IMU delta angles (rad^2)
3 changes: 1 addition & 2 deletions src/drivers/drv_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,13 +68,12 @@
#define DRV_IMU_DEVTYPE_LSM303D 0x11
#define DRV_ACC_DEVTYPE_BMA180 0x12
#define DRV_ACC_DEVTYPE_MPU6000_LEGACY 0x13
#define DRV_ACC_DEVTYPE_ACCELSIM 0x14
#define DRV_IMU_DEVTYPE_SIM 0x14
#define DRV_ACC_DEVTYPE_MPU9250_LEGACY 0x16
#define DRV_IMU_DEVTYPE_BMI160 0x17

#define DRV_IMU_DEVTYPE_MPU6000 0x21
#define DRV_GYR_DEVTYPE_L3GD20 0x22
#define DRV_GYR_DEVTYPE_GYROSIM 0x23
#define DRV_IMU_DEVTYPE_MPU9250 0x24
#define DRV_IMU_DEVTYPE_ICM20649 0x25
#define DRV_IMU_DEVTYPE_ICM42688P 0x26
Expand Down
3 changes: 0 additions & 3 deletions src/drivers/imu/adis16448/ADIS16448.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,9 +115,6 @@ bool ADIS16448::reset()
return false;
}

_px4_accel.set_update_rate(_sample_rate);
_px4_gyro.set_update_rate(_sample_rate);

// Set gyroscope scale to default value.
//if (!set_gyro_dyn_range(GYRO_INITIAL_SENSITIVITY)) {
// return false;
Expand Down
3 changes: 0 additions & 3 deletions src/drivers/imu/adis16477/ADIS16477.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,10 +69,7 @@ ADIS16477::ADIS16477(I2CSPIBusOption bus_option, int bus, int32_t device, enum R
#endif // GPIO_SPI1_RESET_ADIS16477

_px4_accel.set_scale(1.25f * CONSTANTS_ONE_G / 1000.0f); // accel 1.25 mg/LSB
_px4_accel.set_update_rate(ADIS16477_DEFAULT_RATE);

_px4_gyro.set_scale(math::radians(0.025f)); // gyro 0.025 °/sec/LSB
_px4_gyro.set_update_rate(ADIS16477_DEFAULT_RATE);
}

ADIS16477::~ADIS16477()
Expand Down
3 changes: 0 additions & 3 deletions src/drivers/imu/adis16497/ADIS16497.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,9 +84,6 @@ ADIS16497::ADIS16497(I2CSPIBusOption bus_option, int bus, int32_t device, enum R
// Configure hardware reset line
px4_arch_configgpio(GPIO_SPI1_RESET_ADIS16497);
#endif // GPIO_SPI1_RESET_ADIS16497

_px4_accel.set_update_rate(ADIS16497_DEFAULT_RATE);
_px4_gyro.set_update_rate(ADIS16497_DEFAULT_RATE);
}

ADIS16497::~ADIS16497()
Expand Down
1 change: 0 additions & 1 deletion src/drivers/imu/bma180/bma180.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,6 @@ BMA180::BMA180(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotatio
_px4_accel(get_device_id(), ORB_PRIO_MAX, rotation),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read"))
{
_px4_accel.set_update_rate(1000);
}

BMA180::~BMA180()
Expand Down
1 change: 0 additions & 1 deletion src/drivers/imu/bmi055/BMI055_accel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@ BMI055_accel::BMI055_accel(I2CSPIBusOption bus_option, int bus, const char *path
_duplicates(perf_alloc(PC_COUNT, "bmi055_accel_duplicates")),
_got_duplicate(false)
{
_px4_accel.set_update_rate(BMI055_ACCEL_DEFAULT_RATE);
}

BMI055_accel::~BMI055_accel()
Expand Down
1 change: 0 additions & 1 deletion src/drivers/imu/bmi055/BMI055_gyro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@ BMI055_gyro::BMI055_gyro(I2CSPIBusOption bus_option, int bus, const char *path_g
_bad_registers(perf_alloc(PC_COUNT, "bmi055_gyro_bad_registers")),
_duplicates(perf_alloc(PC_COUNT, "bmi055_gyro_duplicates"))
{
_px4_gyro.set_update_rate(BMI055_GYRO_DEFAULT_RATE);
}

BMI055_gyro::~BMI055_gyro()
Expand Down
1 change: 0 additions & 1 deletion src/drivers/imu/bmi088/BMI088_accel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,6 @@ BMI088_accel::BMI088_accel(I2CSPIBusOption bus_option, int bus, const char *path
_duplicates(perf_alloc(PC_COUNT, "bmi088_accel_duplicates")),
_got_duplicate(false)
{
_px4_accel.set_update_rate(BMI088_ACCEL_DEFAULT_RATE);
}

BMI088_accel::~BMI088_accel()
Expand Down
1 change: 0 additions & 1 deletion src/drivers/imu/bmi088/BMI088_gyro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,6 @@ BMI088_gyro::BMI088_gyro(I2CSPIBusOption bus_option, int bus, const char *path_g
_bad_registers(perf_alloc(PC_COUNT, "bmi088_gyro_bad_registers")),
_duplicates(perf_alloc(PC_COUNT, "bmi088_gyro_duplicates"))
{
_px4_gyro.set_update_rate(BMI088_GYRO_DEFAULT_RATE);
}

BMI088_gyro::~BMI088_gyro()
Expand Down
1 change: 0 additions & 1 deletion src/drivers/imu/bmi160/bmi160.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,6 @@ BMI160::BMI160(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotatio
_reset_retries(perf_alloc(PC_COUNT, MODULE_NAME":reset retries")),
_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": duplicates"))
{
_px4_gyro.set_update_rate(BMI160_GYRO_DEFAULT_RATE);
}

BMI160::~BMI160()
Expand Down
1 change: 0 additions & 1 deletion src/drivers/imu/fxas21002c/FXAS21002C.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,6 @@ FXAS21002C::FXAS21002C(device::Device *interface, I2CSPIBusOption bus_option, in
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad register")),
_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": duplicate reading"))
{
_px4_gyro.set_update_rate(FXAS21002C_DEFAULT_RATE);
}

FXAS21002C::~FXAS21002C()
Expand Down
2 changes: 0 additions & 2 deletions src/drivers/imu/fxos8701cq/FXOS8701CQ.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,6 @@ FXOS8701CQ::FXOS8701CQ(device::Device *interface, I2CSPIBusOption bus_option, in
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad reg")),
_accel_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": acc dupe"))
{
_px4_accel.set_update_rate(FXOS8701C_ACCEL_DEFAULT_RATE);

#if !defined(BOARD_HAS_NOISY_FXOS8700_MAG)
_px4_mag.set_scale(0.001f);
#endif
Expand Down
3 changes: 0 additions & 3 deletions src/drivers/imu/invensense/icm20602/ICM20602.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -316,9 +316,6 @@ void ICM20602::ConfigureSampleRate(int sample_rate)

_fifo_accel_samples = math::min(_fifo_empty_interval_us / (1e6f / ACCEL_RATE), (float)FIFO_MAX_SAMPLES);

_px4_accel.set_update_rate(1e6f / _fifo_empty_interval_us);
_px4_gyro.set_update_rate(1e6f / _fifo_empty_interval_us);

ConfigureFIFOWatermark(_fifo_gyro_samples);
}

Expand Down
3 changes: 0 additions & 3 deletions src/drivers/imu/invensense/icm20608g/ICM20608G.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -328,9 +328,6 @@ void ICM20608G::ConfigureSampleRate(int sample_rate)
_fifo_empty_interval_us = _fifo_gyro_samples * (1e6f / GYRO_RATE);

_fifo_accel_samples = math::min(_fifo_empty_interval_us / (1e6f / ACCEL_RATE), (float)FIFO_MAX_SAMPLES);

_px4_accel.set_update_rate(1e6f / _fifo_empty_interval_us);
_px4_gyro.set_update_rate(1e6f / _fifo_empty_interval_us);
}

bool ICM20608G::Configure()
Expand Down
Loading