mirror of https://github.com/ArduPilot/ardupilot
GCS_Common: optical flow comp fields should include flow
This commit is contained in:
parent
b9b00e0f53
commit
70817bb6a7
|
@ -1518,8 +1518,8 @@ void GCS_MAVLINK::send_opticalflow()
|
|||
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