mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Periph: remove PacketDitial from AP_CANManager parameter description
We have removed the class AP_BattMonitor_MPPT_PacketDigital, we should also remove these
This commit is contained in:
parent
d846a81055
commit
d1eedcb4c3
@ -46,11 +46,6 @@
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(HAL_PERIPH_ENABLE_BATTERY_MPPT_PACKETDIGITAL) && HAL_MAX_CAN_PROTOCOL_DRIVERS < 2
|
|
||||||
#error "Battery MPPT PacketDigital driver requires at least two CAN Ports"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
#include "Parameters.h"
|
#include "Parameters.h"
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
@ -78,7 +78,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
// @Param: CAN_PROTOCOL
|
// @Param: CAN_PROTOCOL
|
||||||
// @DisplayName: Enable use of specific protocol to be used on this port
|
// @DisplayName: Enable use of specific protocol to be used on this port
|
||||||
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
|
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
|
||||||
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN,9:PacketDigital
|
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
GARRAY(can_protocol, 0, "CAN_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN),
|
GARRAY(can_protocol, 0, "CAN_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN),
|
||||||
@ -94,7 +94,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
// @Param: CAN2_PROTOCOL
|
// @Param: CAN2_PROTOCOL
|
||||||
// @DisplayName: Enable use of specific protocol to be used on this port
|
// @DisplayName: Enable use of specific protocol to be used on this port
|
||||||
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
|
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
|
||||||
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN,9:PacketDigital
|
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
GARRAY(can_protocol, 1, "CAN2_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN),
|
GARRAY(can_protocol, 1, "CAN2_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN),
|
||||||
@ -112,7 +112,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
// @Param: CAN3_PROTOCOL
|
// @Param: CAN3_PROTOCOL
|
||||||
// @DisplayName: Enable use of specific protocol to be used on this port
|
// @DisplayName: Enable use of specific protocol to be used on this port
|
||||||
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
|
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
|
||||||
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN,9:PacketDigital
|
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
GARRAY(can_protocol, 2, "CAN3_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN),
|
GARRAY(can_protocol, 2, "CAN3_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN),
|
||||||
|
Loading…
Reference in New Issue
Block a user