From 1aab5eec381cfd6fc8043e7512b2cc5f4397614c Mon Sep 17 00:00:00 2001 From: floaledm Date: Mon, 31 Oct 2016 16:59:09 -0500 Subject: [PATCH] AP_Frsky_Telem: send ap_status only once initialized Same as what is found in GCS_MAVLink.cpp for copter --- libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp | 7 +++++-- libraries/AP_Frsky_Telem/AP_Frsky_Telem.h | 1 + 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp index 6be0933511..0f8b0b37ff 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp @@ -50,6 +50,7 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *fi _params.fs_batt_voltage = fs_batt_voltage; // failsafe battery voltage in volts _params.fs_batt_mah = fs_batt_mah; // failsafe reserve capacity in mAh if (ap_valuep == nullptr) { // ap bit-field + _ap.value = 0x2000; // set "initialised" to 1 for rover and plane _ap.valuep = &_ap.value; } else { _ap.valuep = ap_valuep; @@ -111,8 +112,10 @@ void AP_Frsky_Telem::send_SPort_Passthrough(void) _passthrough.params_timer = AP_HAL::millis(); return; } else if ((now - _passthrough.ap_status_timer) > 500) { - send_uint32(DIY_FIRST_ID+1, calc_ap_status()); - _passthrough.ap_status_timer = AP_HAL::millis(); + if ((*_ap.valuep & AP_INITIALIZED_FLAG) > 0) { // send ap status only once vehicle has been initialised + send_uint32(DIY_FIRST_ID+1, calc_ap_status()); + _passthrough.ap_status_timer = AP_HAL::millis(); + } return; } else if ((now - _passthrough.batt_timer) > 1000) { send_uint32(DIY_FIRST_ID+3, calc_batt()); diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h index 8cc57f409d..5cf478cdd7 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h @@ -91,6 +91,7 @@ for FrSky SPort Passthrough #define AP_SSIMPLE_FLAGS 0x6 #define AP_SSIMPLE_OFFSET 4 #define AP_ISFLYING_FLAG 0x80 +#define AP_INITIALIZED_FLAG 0x2000 #define AP_ARMED_OFFSET 8 #define AP_BATT_FS_OFFSET 9 #define AP_EKF_FS_OFFSET 10