Tools: move and rename CAN Driver_Type enumeration

This commit is contained in:
Peter Barker 2023-04-18 19:44:06 +10:00 committed by Peter Barker
parent d0c80f5877
commit ddcfe5e734
4 changed files with 11 additions and 10 deletions

View File

@ -20,7 +20,8 @@
#include "../AP_Bootloader/app_comms.h"
#include <AP_CheckFirmware/AP_CheckFirmware.h>
#include "hwing_esc.h"
#include <AP_CANManager/AP_CANManager.h>
#include <AP_CANManager/AP_CAN.h>
#include <AP_CANManager/AP_SLCANIface.h>
#include <AP_Scripting/AP_Scripting.h>
#include <AP_HAL/CANIface.h>
#include <AP_Stats/AP_Stats.h>
@ -162,7 +163,7 @@ public:
// This allows you to change the protocol and it continues to use the one at boot.
// Without this, changing away from UAVCAN causes loss of comms and you can't
// change the rest of your params or verify it succeeded.
AP_CANManager::Driver_Type can_protocol_cached[HAL_NUM_CAN_IFACES];
AP_CAN::Protocol can_protocol_cached[HAL_NUM_CAN_IFACES];
#endif
#ifdef HAL_PERIPH_ENABLE_MSP

View File

@ -102,7 +102,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @Values: 0:Disabled,1:UAVCAN,4:PiccoloCAN,6:EFI_NWPMU,7:USD1,8:KDECAN
// @User: Advanced
// @RebootRequired: True
GARRAY(can_protocol, 0, "CAN_PROTOCOL", AP_CANManager::Driver_Type_DroneCAN),
GARRAY(can_protocol, 0, "CAN_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)),
// @Param: CAN2_BAUDRATE
// @CopyFieldsFrom: CAN_BAUDRATE
@ -111,7 +111,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @Param: CAN2_PROTOCOL
// @CopyFieldsFrom: CAN_PROTOCOL
GARRAY(can_protocol, 1, "CAN2_PROTOCOL", AP_CANManager::Driver_Type_DroneCAN),
GARRAY(can_protocol, 1, "CAN2_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)),
#endif
#if HAL_NUM_CAN_IFACES >= 3
@ -122,7 +122,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @Param: CAN3_PROTOCOL
// @CopyFieldsFrom: CAN_PROTOCOL
GARRAY(can_protocol, 2, "CAN3_PROTOCOL", AP_CANManager::Driver_Type_DroneCAN),
GARRAY(can_protocol, 2, "CAN3_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)),
#endif
#if HAL_CANFD_SUPPORTED

View File

@ -78,7 +78,7 @@ public:
AP_Int32 can_baudrate[HAL_NUM_CAN_IFACES];
#if HAL_NUM_CAN_IFACES >= 2
AP_Enum<AP_CANManager::Driver_Type> can_protocol[HAL_NUM_CAN_IFACES];
AP_Enum<AP_CAN::Protocol> can_protocol[HAL_NUM_CAN_IFACES];
#endif
#if AP_CAN_SLCAN_ENABLED

View File

@ -1197,7 +1197,7 @@ static void processTx(void)
}
#endif
#if HAL_NUM_CAN_IFACES >= 2
if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_DroneCAN) {
if (periph.can_protocol_cached[ins.index] != AP_CAN::Protocol::DroneCAN) {
continue;
}
#endif
@ -1229,7 +1229,7 @@ static void processRx(void)
continue;
}
#if HAL_NUM_CAN_IFACES >= 2
if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_DroneCAN) {
if (periph.can_protocol_cached[ins.index] != AP_CAN::Protocol::DroneCAN) {
continue;
}
#endif
@ -1485,12 +1485,12 @@ void AP_Periph_FW::can_start()
#if AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz && HAL_NUM_CAN_IFACES >= 2
bool has_uavcan_at_1MHz = false;
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
if (g.can_protocol[i] == AP_CANManager::Driver_Type_DroneCAN && g.can_baudrate[i] == 1000000) {
if (g.can_protocol[i] == AP_CAN::Protocol::DroneCAN && g.can_baudrate[i] == 1000000) {
has_uavcan_at_1MHz = true;
}
}
if (!has_uavcan_at_1MHz) {
g.can_protocol[0].set_and_save(AP_CANManager::Driver_Type_DroneCAN);
g.can_protocol[0].set_and_save(uint8_t(AP_CAN::Protocol::DroneCAN));
g.can_baudrate[0].set_and_save(1000000);
}
#endif // HAL_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz