Browse Source

AP_Baro: uavcan: reindent after WITH_SEMAPHORE change (NFC)

master
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
5e6f02f51e
  1. 34
      libraries/AP_Baro/AP_Baro_UAVCAN.cpp

34
libraries/AP_Baro/AP_Baro_UAVCAN.cpp

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

Loading…
Cancel
Save