AP_CANManager: add support for enabling CANFD

This commit is contained in:
bugobliterator 2022-02-10 13:09:27 +05:30 committed by Andrew Tridgell
parent 1f43c79bfd
commit cb1bc4e613
5 changed files with 16 additions and 6 deletions

View File

@ -35,6 +35,14 @@ const AP_Param::GroupInfo AP_CANManager::CANIface_Params::var_info[] = {
// @User: Advanced
AP_GROUPINFO("BITRATE", 2, AP_CANManager::CANIface_Params, _bitrate, 1000000),
#if HAL_CANFD_SUPPORTED
// @Param: BITRATE
// @DisplayName: Bitrate of CAN interface
// @Description: Bit rate can be set up to from 10000 to 8000000
// @Values: 2:2M, 5:5M, 8:8M
// @User: Advanced
AP_GROUPINFO("FDBITRATE", 3, AP_CANManager::CANIface_Params, _fdbitrate, 8),
#endif
// Index 3 occupied by Param: DEBUG
AP_GROUPEND
};

View File

@ -167,10 +167,10 @@ void AP_CANManager::init()
// instead of a driver
if (_slcan_interface.init_passthrough(i)) {
// we have slcan bridge setup pass that on as can iface
can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, AP_HAL::CANIface::NormalMode);
can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode);
iface = &_slcan_interface;
} else {
can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, AP_HAL::CANIface::NormalMode);
can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode);
}
if (!can_initialised) {

View File

@ -132,6 +132,7 @@ private:
private:
AP_Int8 _driver_number;
AP_Int32 _bitrate;
AP_Int32 _fdbitrate;
};
//Parameter Interface for CANDrivers

View File

@ -153,7 +153,6 @@ bool SLCAN::CANIface::handle_FrameDataExt(const char* cmd)
return push_Frame(f);
}
#if HAL_CANFD_SUPPORTED
/**
* General frame format:
* <type> <id> <dlc> <data>
@ -161,6 +160,9 @@ bool SLCAN::CANIface::handle_FrameDataExt(const char* cmd)
*/
bool SLCAN::CANIface::handle_FDFrameDataExt(const char* cmd)
{
#if HAL_CANFD_SUPPORTED
return false;
#else
AP_HAL::CANFrame f {};
hex2nibble_error = false;
f.canfd = true;
@ -188,8 +190,8 @@ bool SLCAN::CANIface::handle_FDFrameDataExt(const char* cmd)
return false;
}
return push_Frame(f);
}
#endif //#if HAL_CANFD_SUPPORTED
}
bool SLCAN::CANIface::handle_FrameDataStd(const char* cmd)
{

View File

@ -52,9 +52,8 @@ class CANIface: public AP_HAL::CANIface
bool handle_FrameDataStd(const char* cmd);
bool handle_FrameDataExt(const char* cmd);
#if HAL_CANFD_SUPPORTED
bool handle_FDFrameDataExt(const char* cmd);
#endif
// Parsing bytes received on the serial port
inline void addByte(const uint8_t byte);