AP_Baro: uavcan: reindent after WITH_SEMAPHORE change (NFC)

This commit is contained in:
Peter Barker 2019-02-15 12:37:52 +11:00 committed by Andrew Tridgell
parent 78f05492d7
commit 5e6f02f51e

View File

@ -127,29 +127,29 @@ void AP_Baro_UAVCAN::handle_pressure(AP_UAVCAN* ap_uavcan, uint8_t node_id, cons
{
WITH_SEMAPHORE(_sem_registry);
AP_Baro_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, true);
if (driver == nullptr) {
return;
}
{
WITH_SEMAPHORE(driver->_sem_baro);
driver->_pressure = cb.msg->static_pressure;
driver->new_pressure = true;
}
AP_Baro_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, true);
if (driver == nullptr) {
return;
}
{
WITH_SEMAPHORE(driver->_sem_baro);
driver->_pressure = cb.msg->static_pressure;
driver->new_pressure = true;
}
}
void AP_Baro_UAVCAN::handle_temperature(AP_UAVCAN* ap_uavcan, uint8_t node_id, const TemperatureCb &cb)
{
WITH_SEMAPHORE(_sem_registry);
AP_Baro_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, false);
if (driver == nullptr) {
return;
}
{
WITH_SEMAPHORE(driver->_sem_baro);
driver->_temperature = cb.msg->static_temperature - C_TO_KELVIN;
}
AP_Baro_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, false);
if (driver == nullptr) {
return;
}
{
WITH_SEMAPHORE(driver->_sem_baro);
driver->_temperature = cb.msg->static_temperature - C_TO_KELVIN;
}
}
// Read the sensor