PX4-Autopilot/msg/sensor_accel.msg
Daniel Agar 2410b31662
sensors: move accel filtering to sensors/vehicle_acceleration
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
2020-01-29 16:13:38 -05:00

13 lines
505 B
Plaintext

uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample
uint32 device_id # unique device ID for the sensor that does not change between power cycles
float32 x # acceleration in the NED X board axis in m/s^2
float32 y # acceleration in the NED Y board axis in m/s^2
float32 z # acceleration in the NED Z board axis in m/s^2
float32 temperature # temperature in degrees celsius
uint8 ORB_QUEUE_LENGTH = 4