AP_GPS: fix UAVCAN gps message handlers

This commit is contained in:
liang.tang 2018-09-04 21:40:06 -07:00 committed by Andrew Tridgell
parent 2c0b9a16a5
commit 7885b267f0

View File

@ -266,10 +266,9 @@ void AP_GPS_UAVCAN::handle_fix_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node
{ {
if (take_registry()) { if (take_registry()) {
AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id);
if (driver == nullptr) { if (driver != nullptr) {
return; driver->handle_fix_msg(cb);
} }
driver->handle_fix_msg(cb);
give_registry(); give_registry();
} }
} }
@ -278,10 +277,9 @@ void AP_GPS_UAVCAN::handle_aux_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node
{ {
if (take_registry()) { if (take_registry()) {
AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id);
if (driver == nullptr) { if (driver != nullptr) {
return; driver->handle_aux_msg(cb);
} }
driver->handle_aux_msg(cb);
give_registry(); give_registry();
} }
} }