From ab38b12f2c5f428a20b951588390330d25dfa32d Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 10 Jul 2016 17:23:08 -0700 Subject: [PATCH] Plane: adsb specific status updates --- ArduPlane/ArduPlane.cpp | 2 ++ ArduPlane/is_flying.cpp | 1 + ArduPlane/system.cpp | 2 ++ 3 files changed, 5 insertions(+) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 0f45c17cc7..b8bef379d2 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -321,6 +321,8 @@ void Plane::one_second_loop() // make it possible to change orientation at runtime ahrs.set_orientation(); + adsb.set_stall_speed_cm(aparm.airspeed_min); + // sync MAVLink system ID mavlink_system.sysid = g.sysid_this_mav; diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 936539bf49..b94487d9ac 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -153,6 +153,7 @@ void Plane::update_is_flying_5Hz(void) } } previous_is_flying = new_is_flying; + adsb.set_is_flying(new_is_flying); crash_detection_update(); diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 784e638af1..b8dfd08b72 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -482,6 +482,8 @@ void Plane::set_mode(enum FlightMode mode) // start with throttle suppressed in auto_throttle modes throttle_suppressed = auto_throttle_mode; + adsb.set_is_auto_mode(auto_navigation_mode); + if (should_log(MASK_LOG_MODE)) DataFlash.Log_Write_Mode(control_mode);