mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
AP_HAL: make CANFrame data available as uint32_t
this makes the critical sections in CANFrame handling on STM32 faster
This commit is contained in:
parent
44d9d410a1
commit
88e7efcf9c
@ -35,7 +35,10 @@ struct AP_HAL::CANFrame {
|
|||||||
static const uint8_t MaxDataLen = 8;
|
static const uint8_t MaxDataLen = 8;
|
||||||
|
|
||||||
uint32_t id; ///< CAN ID with flags (above)
|
uint32_t id; ///< CAN ID with flags (above)
|
||||||
uint8_t data[MaxDataLen];
|
union {
|
||||||
|
uint8_t data[MaxDataLen];
|
||||||
|
uint32_t data_32[MaxDataLen/4];
|
||||||
|
};
|
||||||
uint8_t dlc; ///< Data Length Code
|
uint8_t dlc; ///< Data Length Code
|
||||||
|
|
||||||
CANFrame() :
|
CANFrame() :
|
||||||
|
Loading…
Reference in New Issue
Block a user