AP_ADSB: move variable into struct like the rest
This commit is contained in:
parent
f7c2df8e91
commit
89271c29ab
@ -547,7 +547,7 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan)
|
||||
}
|
||||
|
||||
uint16_t state = 0;
|
||||
if (_is_in_auto_mode) {
|
||||
if (out_state._is_in_auto_mode) {
|
||||
state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED;
|
||||
}
|
||||
if (!out_state.is_flying) {
|
||||
|
@ -134,7 +134,6 @@ private:
|
||||
|
||||
Location_Class _my_loc;
|
||||
|
||||
bool _is_in_auto_mode;
|
||||
|
||||
// ADSB-IN state. Maintains list of external vehicles
|
||||
struct {
|
||||
@ -159,6 +158,7 @@ private:
|
||||
uint32_t chan_last_ms;
|
||||
UAVIONIX_ADSB_RF_HEALTH status; // transceiver status
|
||||
bool is_flying;
|
||||
bool _is_in_auto_mode;
|
||||
|
||||
// ADSB-OUT configuration
|
||||
struct {
|
||||
|
Loading…
Reference in New Issue
Block a user