mirror of https://github.com/ArduPilot/ardupilot
Tools: rename more variables, types and defines
This commit is contained in:
parent
9e31757b24
commit
c7231240c8
|
@ -102,7 +102,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||
// @Values: 0:Disabled,1:UAVCAN,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),
|
||||
GARRAY(can_protocol, 0, "CAN_PROTOCOL", AP_CANManager::Driver_Type_DroneCAN),
|
||||
|
||||
// @Param: CAN2_BAUDRATE
|
||||
// @DisplayName: Bitrate of CAN2 interface
|
||||
|
@ -118,7 +118,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||
// @Values: 0:Disabled,1:UAVCAN,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),
|
||||
GARRAY(can_protocol, 1, "CAN2_PROTOCOL", AP_CANManager::Driver_Type_DroneCAN),
|
||||
#endif
|
||||
|
||||
#if HAL_NUM_CAN_IFACES >= 3
|
||||
|
@ -136,7 +136,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||
// @Values: 0:Disabled,1:UAVCAN,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),
|
||||
GARRAY(can_protocol, 2, "CAN3_PROTOCOL", AP_CANManager::Driver_Type_DroneCAN),
|
||||
#endif
|
||||
|
||||
#if HAL_CANFD_SUPPORTED
|
||||
|
|
|
@ -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_UAVCAN) {
|
||||
if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_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_UAVCAN) {
|
||||
if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_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_UAVCAN && g.can_baudrate[i] == 1000000) {
|
||||
if (g.can_protocol[i] == AP_CANManager::Driver_Type_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_UAVCAN);
|
||||
g.can_protocol[0].set_and_save(AP_CANManager::Driver_Type_DroneCAN);
|
||||
g.can_baudrate[0].set_and_save(1000000);
|
||||
}
|
||||
#endif // HAL_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz
|
||||
|
|
|
@ -160,7 +160,7 @@ class ExtractFeatures(object):
|
|||
('AP_RPM_{type}_ENABLED', r'AP_RPM_(?P<type>.*)::update',),
|
||||
|
||||
('GPS_MOVING_BASELINE', r'AP_GPS_Backend::calculate_moving_base_yaw\b',),
|
||||
('AP_DRONECAN_SEND_GPS', r'AP_GPS_UAVCAN::instance_exists\b',),
|
||||
('AP_DRONECAN_SEND_GPS', r'AP_GPS_DroneCAN::instance_exists\b',),
|
||||
|
||||
('HAL_WITH_DSP', r'AP_HAL::DSP::find_peaks\b',),
|
||||
('HAL_GYROFFT_ENABLED', r'AP_GyroFFT::AP_GyroFFT\b',),
|
||||
|
|
Loading…
Reference in New Issue