AP_CANManager: set canfd bitrates using CANFD_SUPPORTED opt
also adds option to set as 4MBits/s
This commit is contained in:
parent
4bdbd37731
commit
28b76474cd
@ -38,10 +38,10 @@ const AP_Param::GroupInfo AP_CANManager::CANIface_Params::var_info[] = {
|
||||
#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
|
||||
// @Description: Bit rate can be set up to from 1000000 to 8000000
|
||||
// @Values: 1:1M, 2:2M, 4:4M, 5:5M, 8:8M
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FDBITRATE", 3, AP_CANManager::CANIface_Params, _fdbitrate, 8),
|
||||
AP_GROUPINFO("FDBITRATE", 3, AP_CANManager::CANIface_Params, _fdbitrate, HAL_CANFD_SUPPORTED),
|
||||
#endif
|
||||
// Index 3 occupied by Param: DEBUG
|
||||
AP_GROUPEND
|
||||
|
Loading…
Reference in New Issue
Block a user