AP_UAVCAN: reduce whitespace indentation

This commit is contained in:
Tom Pittenger 2018-03-02 15:37:20 -08:00 committed by Tom Pittenger
parent c49d4aef50
commit 1add05d9a1

View File

@ -108,10 +108,8 @@ static uavcan::equipment::ahrs::Solution _att_state;
void AP_UAVCAN::UAVCAN_AHRS_update(const AP_AHRS_NavEKF &ahrs) void AP_UAVCAN::UAVCAN_AHRS_update(const AP_AHRS_NavEKF &ahrs)
{ {
bool sem_ret = _fix_out_sem->take(1); if (_fix_out_sem->take(1) &&
(fix_out_array[_uavcan_i] != nullptr || fix2_out_array[_uavcan_i] != nullptr)) {
if (sem_ret) {
if (fix_out_array[_uavcan_i] != nullptr || fix2_out_array[_uavcan_i] != nullptr) {
const AP_GPS &cgps = AP::gps(); const AP_GPS &cgps = AP::gps();
Location loc; Location loc;
Vector3f vel_NED; Vector3f vel_NED;
@ -252,9 +250,11 @@ void AP_UAVCAN::UAVCAN_AHRS_update(const AP_AHRS_NavEKF &ahrs)
ts.usec = 0; ts.usec = 0;
_fix_state.timestamp = ts; _fix_state.timestamp = ts;
_fix2_state.timestamp = ts; _fix2_state.timestamp = ts;
_fix_out_sem->give();
} }
if (attitude_out_array[_uavcan_i] != nullptr) { if (_att_out_sem->take(1) && (attitude_out_array[_uavcan_i] != nullptr)) {
uavcan::Timestamp ts; uavcan::Timestamp ts;
ts.usec = AP_HAL::micros64(); ts.usec = AP_HAL::micros64();
_att_state.timestamp = ts; _att_state.timestamp = ts;
@ -285,14 +285,10 @@ void AP_UAVCAN::UAVCAN_AHRS_update(const AP_AHRS_NavEKF &ahrs)
// TODO: extract from EKF // TODO: extract from EKF
//_att_state.linear_acceleration_covariance //_att_state.linear_acceleration_covariance
_att_out_sem->give();
} }
_fix_out_sem->give();
} else {
if (sem_ret) {
_fix_out_sem->give();
}
}
} }
static void gnss_fix_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix>& msg, uint8_t mgr) static void gnss_fix_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix>& msg, uint8_t mgr)