mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
GCS_Common: optical flow comp fields should include flow
This commit is contained in:
parent
1b19d09653
commit
123128deac
@ -1469,8 +1469,8 @@ void GCS_MAVLINK::send_opticalflow(const OpticalFlow &optflow)
|
||||
0, // sensor id is zero
|
||||
flowRate.x,
|
||||
flowRate.y,
|
||||
bodyRate.x,
|
||||
bodyRate.y,
|
||||
flowRate.x - bodyRate.x,
|
||||
flowRate.y - bodyRate.y,
|
||||
optflow.quality(),
|
||||
hagl, // ground distance (in meters) set to zero
|
||||
flowRate.x,
|
||||
|
Loading…
Reference in New Issue
Block a user