From b1311d6d256b89d85f10f9d2afc4e6459cd15100 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 8 Jan 2024 13:07:46 +1100 Subject: [PATCH] AP_OpticalFlow: move simulated height_agl into fdm structure allows value to be shipped via multicast to simulated peripherals --- libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp index 5ac842daba..d238254313 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp @@ -64,9 +64,9 @@ void AP_OpticalFlow_SITL::update(void) // estimate range to centre of image float range; - if (rotmat.c.z > 0.05f && _sitl->height_agl > 0) { + if (rotmat.c.z > 0.05f && _sitl->state.height_agl > 0) { Vector3f relPosSensorEF = rotmat * posRelSensorBF; - range = (_sitl->height_agl - relPosSensorEF.z) / rotmat.c.z; + range = (_sitl->state.height_agl - relPosSensorEF.z) / rotmat.c.z; } else { range = 1e38f; }