AP_FrSky_Telem: eliminate use of Copter's _ap data

This commit is contained in:
Peter Barker 2019-03-02 10:27:11 +11:00 committed by Peter Barker
parent 4f70bdd046
commit 1efc08b54e
2 changed files with 6 additions and 19 deletions

View File

@ -37,7 +37,7 @@ ObjectArray<mavlink_statustext_t> AP_Frsky_Telem::_statustext_queue(FRSKY_TELEM_
/* /*
* init - perform required initialisation * init - perform required initialisation
*/ */
void AP_Frsky_Telem::init(const uint32_t *ap_valuep) void AP_Frsky_Telem::init()
{ {
const AP_SerialManager &serial_manager = AP::serialmanager(); const AP_SerialManager &serial_manager = AP::serialmanager();
@ -58,13 +58,6 @@ void AP_Frsky_Telem::init(const uint32_t *ap_valuep)
snprintf(firmware_buf, sizeof(firmware_buf), "%s %s", AP::fwversion().fw_string, _frame_string); snprintf(firmware_buf, sizeof(firmware_buf), "%s %s", AP::fwversion().fw_string, _frame_string);
queue_message(MAV_SEVERITY_INFO, firmware_buf); queue_message(MAV_SEVERITY_INFO, firmware_buf);
} }
// save main parameters locally
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;
}
} }
if (_port != nullptr) { if (_port != nullptr) {
@ -122,7 +115,7 @@ void AP_Frsky_Telem::send_SPort_Passthrough(void)
return; return;
} }
if ((now - _passthrough.ap_status_timer) >= 500) { if ((now - _passthrough.ap_status_timer) >= 500) {
if (((*_ap.valuep) & AP_INITIALIZED_FLAG) > 0) { // send ap status only once vehicle has been initialised if (gcs().vehicle_initialised()) { // send ap status only once vehicle has been initialised
send_uint32(DIY_FIRST_ID+1, calc_ap_status()); send_uint32(DIY_FIRST_ID+1, calc_ap_status());
_passthrough.ap_status_timer = AP_HAL::millis(); _passthrough.ap_status_timer = AP_HAL::millis();
} }
@ -701,7 +694,8 @@ uint32_t AP_Frsky_Telem::calc_ap_status(void)
// control/flight mode number (limit to 31 (0x1F) since the value is stored on 5 bits) // control/flight mode number (limit to 31 (0x1F) since the value is stored on 5 bits)
ap_status = (uint8_t)((gcs().custom_mode()+1) & AP_CONTROL_MODE_LIMIT); ap_status = (uint8_t)((gcs().custom_mode()+1) & AP_CONTROL_MODE_LIMIT);
// simple/super simple modes flags // simple/super simple modes flags
ap_status |= (uint8_t)((*_ap.valuep) & AP_SSIMPLE_FLAGS)<<AP_SSIMPLE_OFFSET; ap_status |= (uint8_t)(gcs().simple_input_active())<<AP_SIMPLE_OFFSET;
ap_status |= (uint8_t)(gcs().supersimple_input_active())<<AP_SSIMPLE_OFFSET;
// is_flying flag // is_flying flag
ap_status |= (uint8_t)(AP_Notify::flags.flying) << AP_FLYING_OFFSET; ap_status |= (uint8_t)(AP_Notify::flags.flying) << AP_FLYING_OFFSET;
// armed flag // armed flag

View File

@ -85,9 +85,8 @@ for FrSky SPort Passthrough
#define BATT_TOTALMAH_OFFSET 17 #define BATT_TOTALMAH_OFFSET 17
// for autopilot status data // for autopilot status data
#define AP_CONTROL_MODE_LIMIT 0x1F #define AP_CONTROL_MODE_LIMIT 0x1F
#define AP_SSIMPLE_FLAGS 0x6 #define AP_SIMPLE_OFFSET 3
#define AP_SSIMPLE_OFFSET 4 #define AP_SSIMPLE_OFFSET 4
#define AP_INITIALIZED_FLAG 0x2000
#define AP_FLYING_OFFSET 6 #define AP_FLYING_OFFSET 6
#define AP_ARMED_OFFSET 8 #define AP_ARMED_OFFSET 8
#define AP_BATT_FS_OFFSET 9 #define AP_BATT_FS_OFFSET 9
@ -120,7 +119,7 @@ public:
AP_Frsky_Telem &operator=(const AP_Frsky_Telem&) = delete; AP_Frsky_Telem &operator=(const AP_Frsky_Telem&) = delete;
// init - perform required initialisation // init - perform required initialisation
void init(const uint32_t *ap_valuep = nullptr); void init();
// add statustext message to FrSky lib message queue // add statustext message to FrSky lib message queue
void queue_message(MAV_SEVERITY severity, const char *text); void queue_message(MAV_SEVERITY severity, const char *text);
@ -139,12 +138,6 @@ private:
bool _initialised_uart; bool _initialised_uart;
uint16_t _crc; uint16_t _crc;
struct
{
uint32_t value;
const uint32_t *valuep;
} _ap;
uint32_t check_sensor_status_timer; uint32_t check_sensor_status_timer;
uint32_t check_ekf_status_timer; uint32_t check_ekf_status_timer;
uint8_t _paramID; uint8_t _paramID;