mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
HAL_ChibiOS: reduced stack usage in CAN RX handler
This commit is contained in:
parent
c778d14fd3
commit
2d459dccc3
@ -97,6 +97,11 @@ class ChibiOS::CANIface : public AP_HAL::CANIface
|
||||
|
||||
ChibiOS::bxcan::CanType* can_;
|
||||
|
||||
// state for ISR RX handler. We put this in the class to avoid
|
||||
// having to expand the stack size for all threads
|
||||
AP_HAL::CANFrame isr_rx_frame;
|
||||
CanRxItem isr_rx_item;
|
||||
|
||||
CanRxItem rx_buffer[HAL_CAN_RX_QUEUE_SIZE];
|
||||
ByteBuffer rx_bytebuffer_;
|
||||
ObjectBuffer<CanRxItem> rx_queue_;
|
||||
|
@ -519,7 +519,7 @@ void CANIface::handleRxInterrupt(uint8_t fifo_index, uint64_t timestamp_us)
|
||||
/*
|
||||
* Read the frame contents
|
||||
*/
|
||||
AP_HAL::CANFrame frame;
|
||||
AP_HAL::CANFrame &frame = isr_rx_frame;
|
||||
const bxcan::RxMailboxType& rf = can_->RxMailbox[fifo_index];
|
||||
|
||||
if ((rf.RIR & bxcan::RIR_IDE) == 0) {
|
||||
@ -549,7 +549,7 @@ void CANIface::handleRxInterrupt(uint8_t fifo_index, uint64_t timestamp_us)
|
||||
/*
|
||||
* Store with timeout into the FIFO buffer and signal update event
|
||||
*/
|
||||
CanRxItem rx_item;
|
||||
CanRxItem &rx_item = isr_rx_item;
|
||||
rx_item.frame = frame;
|
||||
rx_item.timestamp_us = timestamp_us;
|
||||
rx_item.flags = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user