Files
PX4-Autopilot/msg/VehicleOpticalFlow.msg
Daniel Agar cea185268e msg ROS2 compatibility, microdds_client improvements (timesync, reduced code size, added topics, etc), fastrtps purge
- 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)
2022-10-19 19:36:47 -04:00

22 lines
1.2 KiB
Plaintext

# Optical flow in XYZ body frame in SI units.
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[2] pixel_flow # (radians) accumulated optical flow in radians where a positive value is produced by a RH rotation about the body axis
float32[3] delta_angle # (radians) accumulated gyro radians where a positive value is produced by a RH rotation about the body axis. (NAN if unavailable)
float32 distance_m # (meters) Distance to the center of the flow field (NAN if unavailable)
uint32 integration_timespan_us # (microseconds) accumulation timespan in microseconds
uint8 quality # Average of quality of accumulated frames, 0: bad quality, 255: maximum quality
float32 max_flow_rate # (radians/s) Magnitude of maximum angular which the optical flow sensor can measure reliably
float32 min_ground_distance # (meters) Minimum distance from ground at which the optical flow sensor operates reliably
float32 max_ground_distance # (meters) Maximum distance from ground at which the optical flow sensor operates reliably