mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: helper func
This commit is contained in:
parent
05c8d4cc36
commit
9f27a65f4b
|
@ -432,13 +432,11 @@ void AP_GPS::detect_instance(uint8_t instance)
|
|||
return;
|
||||
}
|
||||
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
|
||||
if (hal.can_mgr[i] == nullptr) {
|
||||
continue;
|
||||
}
|
||||
AP_UAVCAN *uavcan = hal.can_mgr[i]->get_UAVCAN();
|
||||
if (uavcan == nullptr) {
|
||||
AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i);
|
||||
if (ap_uavcan == nullptr) {
|
||||
continue;
|
||||
}
|
||||
|
||||
uint8_t gps_node = uavcan->find_gps_without_listener();
|
||||
if (gps_node == UINT8_MAX) {
|
||||
continue;
|
||||
|
|
|
@ -37,15 +37,14 @@ AP_GPS_UAVCAN::AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UA
|
|||
// For each instance we need to deregister from AP_UAVCAN class
|
||||
AP_GPS_UAVCAN::~AP_GPS_UAVCAN()
|
||||
{
|
||||
if (hal.can_mgr[_manager] == nullptr) {
|
||||
return;
|
||||
}
|
||||
AP_UAVCAN *ap_uavcan = hal.can_mgr[_manager]->get_UAVCAN();
|
||||
AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(_manager);
|
||||
if (ap_uavcan == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
ap_uavcan->remove_gps_listener(this);
|
||||
delete _sem_gnss;
|
||||
|
||||
debug_gps_uavcan(2, "AP_GPS_UAVCAN destructed\n\r");
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue