mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_ADSB: remove deinit()
This commit is contained in:
parent
e94697cb4c
commit
d780e66cc4
@ -55,6 +55,7 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = {
|
|||||||
// @Description: Type of ADS-B hardware for ADSB-in and ADSB-out configuration and operation. If any type is selected then MAVLink based ADSB-in messages will always be enabled
|
// @Description: Type of ADS-B hardware for ADSB-in and ADSB-out configuration and operation. If any type is selected then MAVLink based ADSB-in messages will always be enabled
|
||||||
// @Values: 0:Disabled,1:uAvionix-MAVLink
|
// @Values: 0:Disabled,1:uAvionix-MAVLink
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO_FLAGS("TYPE", 0, AP_ADSB, _type[0], 0, AP_PARAM_FLAG_ENABLE),
|
AP_GROUPINFO_FLAGS("TYPE", 0, AP_ADSB, _type[0], 0, AP_PARAM_FLAG_ENABLE),
|
||||||
|
|
||||||
// index 1 is reserved - was BEHAVIOR
|
// index 1 is reserved - was BEHAVIOR
|
||||||
@ -211,27 +212,12 @@ void AP_ADSB::init(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
* de-initialize and free up some memory
|
|
||||||
*/
|
|
||||||
void AP_ADSB::deinit(void)
|
|
||||||
{
|
|
||||||
if (in_state.vehicle_list != nullptr) {
|
|
||||||
delete [] in_state.vehicle_list;
|
|
||||||
in_state.vehicle_list = nullptr;
|
|
||||||
}
|
|
||||||
for (uint8_t i=0; i<ADSB_MAX_INSTANCES; i++) {
|
|
||||||
if (_backend[i] != nullptr) {
|
|
||||||
delete _backend[i];
|
|
||||||
_backend[i] = nullptr;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
detected_num_instances = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool AP_ADSB::check_startup()
|
bool AP_ADSB::check_startup()
|
||||||
{
|
{
|
||||||
|
if (_init_failed) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
bool all_backends_disabled = true;
|
bool all_backends_disabled = true;
|
||||||
for (uint8_t instance=0; instance<ADSB_MAX_INSTANCES; instance++) {
|
for (uint8_t instance=0; instance<ADSB_MAX_INSTANCES; instance++) {
|
||||||
if (_type[instance] > 0) {
|
if (_type[instance] > 0) {
|
||||||
@ -240,10 +226,7 @@ bool AP_ADSB::check_startup()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (all_backends_disabled || _init_failed) {
|
if (all_backends_disabled) {
|
||||||
if (in_state.vehicle_list != nullptr) {
|
|
||||||
deinit();
|
|
||||||
}
|
|
||||||
// nothing to do
|
// nothing to do
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
@ -359,7 +342,7 @@ void AP_ADSB::update(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
for (uint8_t i=0; i<detected_num_instances; i++) {
|
for (uint8_t i=0; i<detected_num_instances; i++) {
|
||||||
if (_backend[i] != nullptr) {
|
if (_backend[i] != nullptr && _type[i].get() != (int8_t)Type::None) {
|
||||||
_backend[i]->update();
|
_backend[i]->update();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -143,7 +143,6 @@ private:
|
|||||||
|
|
||||||
// initialize vehicle_list
|
// initialize vehicle_list
|
||||||
void init();
|
void init();
|
||||||
void deinit();
|
|
||||||
|
|
||||||
// check to see if we are initialized (and possibly do initialization)
|
// check to see if we are initialized (and possibly do initialization)
|
||||||
bool check_startup();
|
bool check_startup();
|
||||||
|
Loading…
Reference in New Issue
Block a user