mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-02-07 02:32:25 +08:00
- update all msgs to be directly compatible with ROS2 - microdds_client improvements - timesync - reduced code size - add to most default builds if we can afford it - lots of other little changes - purge fastrtps (I tried to save this multiple times, but kept hitting roadblocks)
14 lines
891 B
Plaintext
14 lines
891 B
Plaintext
uint64 timestamp # time since system start (microseconds)
|
|
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
|
|
|
|
float32[2] vel_body # velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s)
|
|
float32[2] vel_ne # same as vel_body but in local frame (m/s)
|
|
|
|
float32[2] flow_uncompensated_integral # integrated optical flow measurement (rad)
|
|
float32[2] flow_compensated_integral # integrated optical flow measurement compensated for angular motion (rad)
|
|
|
|
float32[3] gyro_rate # gyro measurement synchronized with flow measurements (rad/s)
|
|
float32[3] gyro_rate_integral # gyro measurement integrated to flow rate and synchronized with flow measurements (rad)
|
|
|
|
# TOPICS estimator_optical_flow_vel vehicle_optical_flow_vel
|