diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 022c4bcfe8..8983badc0c 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -217,19 +217,7 @@ private: RangeFinder rangefinder {serial_manager}; - struct { - bool in_range:1; - bool have_initial_reading:1; - bool in_use:1; - float initial_range; - float correction; - float initial_correction; - float last_stable_correction; - uint32_t last_correction_time_ms; - uint8_t in_range_count; - float height_estimate; - float last_distance; - } rangefinder_state; + AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state; AP_RPM rpm_sensor; diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 889994bc16..0f4e379fd2 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -43,6 +43,20 @@ public: AP_Float land_flare_sec; AP_Float land_pre_flare_airspeed; AP_Int8 stall_prevention; + + struct Rangefinder_State { + bool in_range:1; + bool have_initial_reading:1; + bool in_use:1; + float initial_range; + float correction; + float initial_correction; + float last_stable_correction; + uint32_t last_correction_time_ms; + uint8_t in_range_count; + float height_estimate; + float last_distance; + }; }; /*