AP_Airspeed: uavcan: use WITH_SEMAPHORE in place of give/take _registry

This commit is contained in:
Peter Barker 2019-02-15 12:40:06 +11:00 committed by Andrew Tridgell
parent 5e6f02f51e
commit c96cdf1f16
2 changed files with 3 additions and 22 deletions

View File

@ -41,21 +41,9 @@ void AP_Airspeed_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan)
} }
} }
bool AP_Airspeed_UAVCAN::take_registry()
{
return _sem_registry.take(HAL_SEMAPHORE_BLOCK_FOREVER);
}
void AP_Airspeed_UAVCAN::give_registry()
{
_sem_registry.give();
}
AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _instance) AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _instance)
{ {
if (!take_registry()) { WITH_SEMAPHORE(_sem_registry);
return nullptr;
}
AP_Airspeed_UAVCAN* backend = nullptr; AP_Airspeed_UAVCAN* backend = nullptr;
@ -80,8 +68,6 @@ AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _
} }
} }
give_registry();
return backend; return backend;
} }
@ -123,7 +109,8 @@ AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan,
void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AirspeedCb &cb) void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AirspeedCb &cb)
{ {
if (take_registry()) { WITH_SEMAPHORE(_sem_registry);
AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id);
if (driver != nullptr) { if (driver != nullptr) {
@ -132,9 +119,6 @@ void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id,
driver->_temperature = cb.msg->static_air_temperature - C_TO_KELVIN; driver->_temperature = cb.msg->static_air_temperature - C_TO_KELVIN;
driver->_last_sample_time_ms = AP_HAL::millis(); driver->_last_sample_time_ms = AP_HAL::millis();
} }
give_registry();
}
} }
bool AP_Airspeed_UAVCAN::init() bool AP_Airspeed_UAVCAN::init()

View File

@ -23,9 +23,6 @@ public:
static AP_Airspeed_Backend* probe(AP_Airspeed &_fronted, uint8_t _instance); static AP_Airspeed_Backend* probe(AP_Airspeed &_fronted, uint8_t _instance);
private: private:
static bool take_registry();
static void give_registry();
static void handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AirspeedCb &cb); static void handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AirspeedCb &cb);