AP_HAL_PX4: reducing indenting by linearizing the logic

This commit is contained in:
Eugene Shamaev 2018-03-09 10:30:54 +02:00 committed by Tom Pittenger
parent 7dd8308a8c
commit 2a6387fd3b
3 changed files with 237 additions and 227 deletions

View File

@ -110,34 +110,38 @@ void BusEvent::signalFromInterrupt()
static void handleTxInterrupt(uint8_t iface_index) static void handleTxInterrupt(uint8_t iface_index)
{ {
if (iface_index < CAN_STM32_NUM_IFACES) { if (iface_index >= CAN_STM32_NUM_IFACES) {
return;
}
uint64_t utc_usec = clock::getUtcUSecFromCanInterrupt(); uint64_t utc_usec = clock::getUtcUSecFromCanInterrupt();
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) { for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
if (hal.can_mgr[i] != nullptr) { if (hal.can_mgr[i] == nullptr) {
continue;
}
PX4CAN* iface = ((PX4CANManager*) hal.can_mgr[i])->getIface_out_to_in(iface_index); PX4CAN* iface = ((PX4CANManager*) hal.can_mgr[i])->getIface_out_to_in(iface_index);
if (iface != nullptr) { if (iface != nullptr) {
iface->handleTxInterrupt(utc_usec); iface->handleTxInterrupt(utc_usec);
} }
} }
}
}
} }
static void handleRxInterrupt(uint8_t iface_index, uint8_t fifo_index) static void handleRxInterrupt(uint8_t iface_index, uint8_t fifo_index)
{ {
if (iface_index < CAN_STM32_NUM_IFACES) { if (iface_index >= CAN_STM32_NUM_IFACES) {
return;
}
uint64_t utc_usec = clock::getUtcUSecFromCanInterrupt(); uint64_t utc_usec = clock::getUtcUSecFromCanInterrupt();
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) { for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
if (hal.can_mgr[i] != nullptr) { if (hal.can_mgr[i] == nullptr) {
continue;
}
PX4CAN* iface = ((PX4CANManager*) hal.can_mgr[i])->getIface_out_to_in(iface_index); PX4CAN* iface = ((PX4CANManager*) hal.can_mgr[i])->getIface_out_to_in(iface_index);
if (iface != nullptr) { if (iface != nullptr) {
iface->handleRxInterrupt(fifo_index, utc_usec); iface->handleRxInterrupt(fifo_index, utc_usec);
} }
} }
}
}
} }
const uint32_t PX4CAN::TSR_ABRQx[PX4CAN::NumTxMailboxes] = { bxcan::TSR_ABRQ0, bxcan::TSR_ABRQ1, bxcan::TSR_ABRQ2 }; const uint32_t PX4CAN::TSR_ABRQx[PX4CAN::NumTxMailboxes] = { bxcan::TSR_ABRQ0, bxcan::TSR_ABRQ1, bxcan::TSR_ABRQ2 };
@ -238,12 +242,10 @@ int PX4CAN::computeTimings(const uint32_t target_bitrate, Timings& out_timings)
bs1(arg_bs1), bs2(uint8_t(bs1_bs2_sum - bs1)), sample_point_permill( bs1(arg_bs1), bs2(uint8_t(bs1_bs2_sum - bs1)), sample_point_permill(
uint16_t(1000 * (1 + bs1) / (1 + bs1 + bs2))) uint16_t(1000 * (1 + bs1) / (1 + bs1 + bs2)))
{ {
if (bs1_bs2_sum <= arg_bs1) { if (bs1_bs2_sum <= arg_bs1 && (AP_BoardConfig_CAN::get_can_debug() >= 1)) {
if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
AP_HAL::panic("PX4CAN::computeTimings bs1_bs2_sum <= arg_bs1"); AP_HAL::panic("PX4CAN::computeTimings bs1_bs2_sum <= arg_bs1");
} }
} }
}
bool isValid() const bool isValid() const
{ {
@ -385,7 +387,10 @@ int16_t PX4CAN::receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_
int16_t PX4CAN::configureFilters(const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs) int16_t PX4CAN::configureFilters(const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs)
{ {
if (num_configs <= NumFilters) { if (num_configs > NumFilters) {
return -ErrFilterNumConfigs;
}
CriticalSectionLocker lock; CriticalSectionLocker lock;
can_->FMR |= bxcan::FMR_FINIT; can_->FMR |= bxcan::FMR_FINIT;
@ -445,9 +450,6 @@ int16_t PX4CAN::configureFilters(const uavcan::CanFilterConfig* filter_configs,
can_->FMR &= ~bxcan::FMR_FINIT; can_->FMR &= ~bxcan::FMR_FINIT;
return 0; return 0;
}
return -ErrFilterNumConfigs;
} }
bool PX4CAN::waitMsrINakBitStateChange(bool target_state) bool PX4CAN::waitMsrINakBitStateChange(bool target_state)
@ -601,7 +603,7 @@ void PX4CAN::handleTxInterrupt(const uint64_t utc_usec)
handleTxMailboxInterrupt(2, txok, utc_usec); handleTxMailboxInterrupt(2, txok, utc_usec);
} }
if(update_event_ != nullptr) { if (update_event_ != nullptr) {
update_event_->signalFromInterrupt(); update_event_->signalFromInterrupt();
} }
@ -610,7 +612,9 @@ void PX4CAN::handleTxInterrupt(const uint64_t utc_usec)
void PX4CAN::handleRxInterrupt(uint8_t fifo_index, uint64_t utc_usec) void PX4CAN::handleRxInterrupt(uint8_t fifo_index, uint64_t utc_usec)
{ {
if (fifo_index < 2) { if (fifo_index >= 2) {
return;
}
volatile uint32_t* const rfr_reg = (fifo_index == 0) ? &can_->RF0R : &can_->RF1R; volatile uint32_t* const rfr_reg = (fifo_index == 0) ? &can_->RF0R : &can_->RF1R;
if ((*rfr_reg & bxcan::RFR_FMP_MASK) == 0) { if ((*rfr_reg & bxcan::RFR_FMP_MASK) == 0) {
@ -664,18 +668,19 @@ void PX4CAN::handleRxInterrupt(uint8_t fifo_index, uint64_t utc_usec)
rx_queue_.push(frm); rx_queue_.push(frm);
had_activity_ = true; had_activity_ = true;
if(update_event_ != nullptr) { if (update_event_ != nullptr) {
update_event_->signalFromInterrupt(); update_event_->signalFromInterrupt();
} }
pollErrorFlagsFromISR(); pollErrorFlagsFromISR();
}
} }
void PX4CAN::pollErrorFlagsFromISR() void PX4CAN::pollErrorFlagsFromISR()
{ {
const uint8_t lec = uint8_t((can_->ESR & bxcan::ESR_LEC_MASK) >> bxcan::ESR_LEC_SHIFT); const uint8_t lec = uint8_t((can_->ESR & bxcan::ESR_LEC_MASK) >> bxcan::ESR_LEC_SHIFT);
if (lec != 0) { if (lec == 0) {
return;
}
can_->ESR = 0; can_->ESR = 0;
error_cnt_++; error_cnt_++;
@ -688,7 +693,6 @@ void PX4CAN::pollErrorFlagsFromISR()
served_aborts_cnt_++; served_aborts_cnt_++;
} }
} }
}
} }
void PX4CAN::discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time) void PX4CAN::discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time)
@ -799,10 +803,12 @@ int32_t PX4CAN::available()
int32_t PX4CAN::tx_pending() int32_t PX4CAN::tx_pending()
{ {
int32_t ret = -1; if (!initialized_) {
return -1;
}
int32_t ret = 0;
if (initialized_) {
ret = 0;
CriticalSectionLocker lock; CriticalSectionLocker lock;
for (int mbx = 0; mbx < NumTxMailboxes; mbx++) { for (int mbx = 0; mbx < NumTxMailboxes; mbx++) {
@ -810,7 +816,6 @@ int32_t PX4CAN::tx_pending()
ret++; ret++;
} }
} }
}
return ret; return ret;
} }
@ -835,7 +840,10 @@ uavcan::CanSelectMasks PX4CANManager::makeSelectMasks(const uavcan::CanFrame* (&
uavcan::CanSelectMasks msk; uavcan::CanSelectMasks msk;
for (uint8_t i = 0; i < _ifaces_num; i++) { for (uint8_t i = 0; i < _ifaces_num; i++) {
if (ifaces[i] != nullptr) { if (ifaces[i] == nullptr) {
continue;
}
if (!ifaces[i]->isRxBufferEmpty()) { if (!ifaces[i]->isRxBufferEmpty()) {
msk.read |= 1 << i; msk.read |= 1 << i;
} }
@ -846,7 +854,6 @@ uavcan::CanSelectMasks PX4CANManager::makeSelectMasks(const uavcan::CanFrame* (&
} }
} }
} }
}
return msk; return msk;
} }
@ -871,14 +878,15 @@ int16_t PX4CANManager::select(uavcan::CanSelectMasks& inout_masks,
const uavcan::MonotonicTime time = clock::getMonotonic(); const uavcan::MonotonicTime time = clock::getMonotonic();
for (uint8_t i = 0; i < _ifaces_num; i++) { for (uint8_t i = 0; i < _ifaces_num; i++) {
if (ifaces[i] != nullptr) { if (ifaces[i] == nullptr) {
continue;
}
ifaces[i]->discardTimedOutTxMailboxes(time); ifaces[i]->discardTimedOutTxMailboxes(time);
{ {
CriticalSectionLocker cs_locker; CriticalSectionLocker cs_locker;
ifaces[i]->pollErrorFlagsFromISR(); ifaces[i]->pollErrorFlagsFromISR();
} }
} }
}
inout_masks = makeSelectMasks(pending_tx); // Check if we already have some of the requested events inout_masks = makeSelectMasks(pending_tx); // Check if we already have some of the requested events
if ((inout_masks.read & in_masks.read) != 0 || (inout_masks.write & in_masks.write) != 0) { if ((inout_masks.read & in_masks.read) != 0 || (inout_masks.write & in_masks.write) != 0) {
@ -951,11 +959,12 @@ void PX4CANManager::initOnce(uint8_t can_number)
int PX4CANManager::init(const uint32_t bitrate, const PX4CAN::OperatingMode mode, uint8_t can_number) int PX4CANManager::init(const uint32_t bitrate, const PX4CAN::OperatingMode mode, uint8_t can_number)
{ {
int res = -ErrNotImplemented; if (can_number >= CAN_STM32_NUM_IFACES) {
return -ErrNotImplemented;
}
static bool initialized_once[CAN_STM32_NUM_IFACES]; static bool initialized_once[CAN_STM32_NUM_IFACES];
if (can_number < CAN_STM32_NUM_IFACES) { int res = 0;
res = 0;
if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) { if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) {
printf("PX4CANManager::init Bitrate %lu mode %d bus %d\n\r", static_cast<unsigned long>(bitrate), printf("PX4CANManager::init Bitrate %lu mode %d bus %d\n\r", static_cast<unsigned long>(bitrate),
@ -1007,7 +1016,6 @@ int PX4CANManager::init(const uint32_t bitrate, const PX4CAN::OperatingMode mode
if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) { if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) {
printf("PX4CANManager::init CAN drv init OK, res = %d\n\r", res); printf("PX4CANManager::init CAN drv init OK, res = %d\n\r", res);
} }
}
return res; return res;
} }

View File

@ -105,16 +105,18 @@ void PX4Scheduler::create_uavcan_thread()
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO); pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) { for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
if (hal.can_mgr[i] != nullptr) { if (hal.can_mgr[i] == nullptr) {
if (hal.can_mgr[i]->get_UAVCAN() != nullptr) { continue;
}
if (hal.can_mgr[i]->get_UAVCAN() == nullptr) {
continue;
}
_uavcan_thread_arg *arg = new _uavcan_thread_arg; _uavcan_thread_arg *arg = new _uavcan_thread_arg;
arg->sched = this; arg->sched = this;
arg->uavcan_number = i; arg->uavcan_number = i;
pthread_create(&_uavcan_thread_ctx, &thread_attr, &PX4Scheduler::_uavcan_thread, arg); pthread_create(&_uavcan_thread_ctx, &thread_attr, &PX4Scheduler::_uavcan_thread, arg);
} }
}
}
#endif #endif
} }