Skip to content

Commit 5d245bf

Browse files
committed
GCS_MAVLink: Use flow rates and add ground distance field in MAVLink driver
1 parent 7466adf commit 5d245bf

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

libraries/GCS_MAVLink/GCS_Common.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2914,6 +2914,7 @@ void GCS_MAVLINK::send_opticalflow()
29142914
// get rates from sensor
29152915
const Vector2f &flowRate = optflow->flowRate();
29162916
const Vector2f &bodyRate = optflow->bodyRate();
2917+
const float groundDistance = optflow->groundDistance();
29172918

29182919
float hagl = 0;
29192920
#if AP_AHRS_ENABLED
@@ -2932,7 +2933,7 @@ void GCS_MAVLINK::send_opticalflow()
29322933
flowRate.x - bodyRate.x,
29332934
flowRate.y - bodyRate.y,
29342935
optflow->quality(),
2935-
hagl, // ground distance (in meters) set to zero
2936+
groundDistance, // ground distance (in meters) set to zero
29362937
flowRate.x,
29372938
flowRate.y);
29382939
}

0 commit comments

Comments
 (0)