2020-05-31 08:43:28 -03:00
|
|
|
/*
|
|
|
|
* This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
2021-06-20 03:30:07 -03:00
|
|
|
#if HAL_CANMANAGER_ENABLED
|
2020-05-31 08:43:28 -03:00
|
|
|
#include "AP_CANManager.h"
|
|
|
|
|
|
|
|
// table of user settable CAN bus parameters
|
|
|
|
const AP_Param::GroupInfo AP_CANManager::CANIface_Params::var_info[] = {
|
|
|
|
// @Param: DRIVER
|
|
|
|
// @DisplayName: Index of virtual driver to be used with physical CAN interface
|
|
|
|
// @Description: Enabling this option enables use of CAN buses.
|
2021-08-23 12:23:46 -03:00
|
|
|
// @Values: 0:Disabled,1:First driver,2:Second driver,3:Third driver
|
2020-05-31 08:43:28 -03:00
|
|
|
// @User: Standard
|
|
|
|
// @RebootRequired: True
|
|
|
|
AP_GROUPINFO_FLAGS("DRIVER", 1, AP_CANManager::CANIface_Params, _driver_number, HAL_CAN_DRIVER_DEFAULT, AP_PARAM_FLAG_ENABLE),
|
|
|
|
|
|
|
|
// @Param: BITRATE
|
|
|
|
// @DisplayName: Bitrate of CAN interface
|
|
|
|
// @Description: Bit rate can be set up to from 10000 to 1000000
|
|
|
|
// @Range: 10000 1000000
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("BITRATE", 2, AP_CANManager::CANIface_Params, _bitrate, 1000000),
|
|
|
|
|
2022-02-10 03:39:27 -04:00
|
|
|
#if HAL_CANFD_SUPPORTED
|
2022-03-12 20:24:02 -04:00
|
|
|
// @Param: FDBITRATE
|
|
|
|
// @DisplayName: Bitrate of CANFD interface
|
2022-03-01 05:12:01 -04:00
|
|
|
// @Description: Bit rate can be set up to from 1000000 to 8000000
|
|
|
|
// @Values: 1:1M, 2:2M, 4:4M, 5:5M, 8:8M
|
2022-02-10 03:39:27 -04:00
|
|
|
// @User: Advanced
|
2022-03-01 05:12:01 -04:00
|
|
|
AP_GROUPINFO("FDBITRATE", 3, AP_CANManager::CANIface_Params, _fdbitrate, HAL_CANFD_SUPPORTED),
|
2022-02-10 03:39:27 -04:00
|
|
|
#endif
|
2020-09-13 21:28:39 -03:00
|
|
|
// Index 3 occupied by Param: DEBUG
|
2020-05-31 08:43:28 -03:00
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
|
|
|
#endif
|