From c583edc34b6609861c1d46dcbadbc9fa83a1e568 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 8 Jan 2024 13:07:46 +1100 Subject: [PATCH] AP_Proximity: move simulated height_agl into fdm structure allows value to be shipped via multicast to simulated peripherals --- libraries/AP_Proximity/AP_Proximity_SITL.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.cpp b/libraries/AP_Proximity/AP_Proximity_SITL.cpp index 1d72a8ebed..6c1e6dcdb7 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_SITL.cpp @@ -131,7 +131,7 @@ float AP_Proximity_SITL::distance_min() const bool AP_Proximity_SITL::get_upward_distance(float &distance) const { // return distance to fence altitude - distance = MAX(0.0f, fence_alt_max->get() - sitl->height_agl); + distance = MAX(0.0f, fence_alt_max->get() - sitl->state.height_agl); return true; }