I've added a queue depth of 4 for sensor_accel and sensor_gyro. This is initially added because it's not always possible for the `vehicle_acceleration` to keep up with every publication of the primary accelerator as it runs in the same thread as ekf2, various controllers, etc.
Later this mechanism will be used in a few areas
- rate limit `vehicle_angular_velocity` and `vehicle_acceleration` without missing any raw data
- move IMU integration to `vehicle_imu` and out of the actual driver threads, eliminating the need for sensor_accel_integrated and sensor_gyro_integrated
- integrate raw gyro synchronized with optical flow measurements
- introduces parameter IMU_DGYRO_CUTOFF to configure the angular acceleration low pass filter
- the angular acceleration is computed by differentiating angular velocity after the notch filter (IMU_GYRO_NF_FREQ & IMU_GYRO_NF_BW) is applied
Co-authored-by: Julien Lecoeur <jlecoeur@users.noreply.github.com>
- gyro filtering (low-pass and notch) only performed on primary gyro in `sensors/vehicle_angular_velocity` instead of every gyro in `PX4Gyroscope`
- sample rate is calculated from actual updates (the fixed value was slightly wrong in many cases, and very wrong in a few)
- In the FIFO case the array is now averaged and published in `sensor_gyro` for filtering downstream. I'll update this in the future to use the full FIFO array (if available), but right now it should be fine.
- split out integrated data into new standalone messages (sensor_accel_integrated and sensor_gyro_integrated)
- publish sensor_gyro at full rate and remove sensor_gyro_control
- limit sensor status publications to 10 Hz
- remove unused accel/gyro raw ADC fields
- add device IDs to sensor_bias and sensor_correction
- vehicle_angular_velocity/vehicle_acceleration: check device ids before using bias and corrections
and remove the px4_ prefix, except for px4_config.h.
command to update includes:
for k in app.h atomic.h cli.h console_buffer.h defines.h getopt.h i2c.h init.h log.h micro_hal.h module.h module_params.h param.h param_macros.h posix.h sem.h sem.hpp shmem.h shutdown.h tasks.h time.h workqueue.h; do for i in $(grep -rl 'include <px4_'$k src platforms boards); do sed -i 's/#include <px4_'$k'/#include <px4_platform_common\/'$k/ $i; done; done
for in $(grep -rl 'include <px4_config.h' src platforms boards); do sed -i 's/#include <px4_config.h/#include <px4_platform_common\/px4_config.h'/ $i; done
Transitional headers for submodules are added (px4_{defines,log,time}.h)
Some of these perf counters were useful during initial development, but realistically aren't needed anymore, some are redundant when we can now see the average interval from `work_queue status` and some of them simply aren't worth the cost at higher rates.
* adds a work_queue systemcmd that will bring a tree view of all active work queues and work items
* WorkQueues now track attached WorkItems and will shutdown when the last WorkItem is detached
Script to update include paths:
for i in $(grep -rl 'include <px4_work_queue' src platforms); do sed -i 's/#include <px4_work_queue/#include <px4_platform_common\/px4_work_queue/' $i; done