AP_HAL: set CANFrame max data length based on CANFD availability

This commit is contained in:
Siddharth Purohit 2021-05-17 23:05:29 +05:30 committed by Andrew Tridgell
parent 563e69e64c
commit 5bc65bb54e
2 changed files with 8 additions and 7 deletions

View File

@ -19,6 +19,7 @@
#include <stdint.h> #include <stdint.h>
#include "AP_HAL_Namespace.h" #include "AP_HAL_Namespace.h"
#include "AP_HAL_Boards.h"
class ExpandingString; class ExpandingString;
@ -32,8 +33,13 @@ struct AP_HAL::CANFrame {
static const uint32_t FlagRTR = 1U << 30; ///< Remote transmission request static const uint32_t FlagRTR = 1U << 30; ///< Remote transmission request
static const uint32_t FlagERR = 1U << 29; ///< Error frame static const uint32_t FlagERR = 1U << 29; ///< Error frame
#if HAL_CANFD_SUPPORTED
static const uint8_t NonFDCANMaxDataLen = 8;
static const uint8_t MaxDataLen = 64; static const uint8_t MaxDataLen = 64;
#else
static const uint8_t NonFDCANMaxDataLen = 8;
static const uint8_t MaxDataLen = 8;
#endif
uint32_t id; ///< CAN ID with flags (above) uint32_t id; ///< CAN ID with flags (above)
union { union {
uint8_t data[MaxDataLen]; uint8_t data[MaxDataLen];
@ -138,6 +144,7 @@ struct AP_HAL::CANFrame {
} }
return 64; return 64;
} }
static uint8_t dataLengthToDlc(uint8_t data_length) { static uint8_t dataLengthToDlc(uint8_t data_length) {
if (data_length <= 8) { if (data_length <= 8) {
return data_length; return data_length;

View File

@ -128,9 +128,3 @@
#ifndef HAL_BOARD_STORAGE_DIRECTORY #ifndef HAL_BOARD_STORAGE_DIRECTORY
#define HAL_BOARD_STORAGE_DIRECTORY "/APM" #define HAL_BOARD_STORAGE_DIRECTORY "/APM"
#endif #endif
#if defined(STM32H7XX) || defined(STM32G4)
#define HAL_CANFD_SUPPORTED 1
# else
#define HAL_CANFD_SUPPORTED 0
#endif