mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Baro: uavcan: reindent after WITH_SEMAPHORE change (NFC)
This commit is contained in:
parent
78f05492d7
commit
5e6f02f51e
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user