From d1eedcb4c3c3b583ff627194455bd1b1da828699 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Fri, 17 Dec 2021 11:35:07 +0530 Subject: [PATCH] AP_Periph: remove PacketDitial from AP_CANManager parameter description We have removed the class AP_BattMonitor_MPPT_PacketDigital, we should also remove these --- Tools/AP_Periph/AP_Periph.h | 5 ----- Tools/AP_Periph/Parameters.cpp | 6 +++--- 2 files changed, 3 insertions(+), 8 deletions(-) diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 95519052b5..431927d4ee 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -46,11 +46,6 @@ #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" #if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 83944fe6ba..64fae53d67 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -78,7 +78,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Param: CAN_PROTOCOL // @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 - // @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 // @RebootRequired: True 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 // @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 - // @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 // @RebootRequired: True 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 // @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 - // @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 // @RebootRequired: True GARRAY(can_protocol, 2, "CAN3_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN),