AP_CANManager: rename AP_UAVCAN to AP_DroneCAN

This commit is contained in:
Andrew Tridgell 2023-04-07 10:18:01 +10:00
parent a03c395cce
commit dbe91670a9
4 changed files with 10 additions and 10 deletions

View File

@ -19,7 +19,7 @@
#include "AP_CANManager.h"
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_UAVCAN/AP_UAVCAN.h>
#include <AP_DroneCAN/AP_DroneCAN.h>
#include <AP_PiccoloCAN/AP_PiccoloCAN.h>
#include "AP_CANTester.h"
#include <AP_KDECAN/AP_KDECAN.h>
@ -38,8 +38,8 @@ const AP_Param::GroupInfo AP_CANManager::CANDriver_Params::var_info[] = {
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
// @Group: UC_
// @Path: ../AP_UAVCAN/AP_UAVCAN.cpp
AP_SUBGROUPPTR(_uavcan, "UC_", 2, AP_CANManager::CANDriver_Params, AP_UAVCAN),
// @Path: ../AP_DroneCAN/AP_DroneCAN.cpp
AP_SUBGROUPPTR(_uavcan, "UC_", 2, AP_CANManager::CANDriver_Params, AP_DroneCAN),
#endif
#if (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub))

View File

@ -24,7 +24,7 @@
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_UAVCAN/AP_UAVCAN.h>
#include <AP_DroneCAN/AP_DroneCAN.h>
#include <AP_KDECAN/AP_KDECAN.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_PiccoloCAN/AP_PiccoloCAN.h>
@ -205,14 +205,14 @@ void AP_CANManager::init()
// Allocate the set type of Driver
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
if (drv_type[drv_num] == Driver_Type_UAVCAN) {
_drivers[drv_num] = _drv_param[drv_num]._uavcan = new AP_UAVCAN(drv_num);
_drivers[drv_num] = _drv_param[drv_num]._uavcan = new AP_DroneCAN(drv_num);
if (_drivers[drv_num] == nullptr) {
AP_BoardConfig::allocation_error("uavcan %d", i + 1);
continue;
}
AP_Param::load_object_from_eeprom((AP_UAVCAN*)_drivers[drv_num], AP_UAVCAN::var_info);
AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[drv_num], AP_DroneCAN::var_info);
} else
#endif
if (drv_type[drv_num] == Driver_Type_KDECAN) {
@ -289,14 +289,14 @@ void AP_CANManager::init()
WITH_SEMAPHORE(_sem);
for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {
if ((Driver_Type) _drv_param[i]._driver_type.get() == Driver_Type_UAVCAN) {
_drivers[i] = _drv_param[i]._uavcan = new AP_UAVCAN(i);
_drivers[i] = _drv_param[i]._uavcan = new AP_DroneCAN(i);
if (_drivers[i] == nullptr) {
AP_BoardConfig::allocation_error("uavcan %d", i + 1);
continue;
}
AP_Param::load_object_from_eeprom((AP_UAVCAN*)_drivers[i], AP_UAVCAN::var_info);
AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[i], AP_DroneCAN::var_info);
_drivers[i]->init(i, true);
_driver_type_cache[i] = (Driver_Type) _drv_param[i]._driver_type.get();
}

View File

@ -25,7 +25,7 @@
#include <AP_SerialManager/AP_SerialManager.h>
#include <stdio.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_UAVCAN/AP_UAVCAN.h>
#include <AP_DroneCAN/AP_DroneCAN.h>
#include <uavcan/protocol/dynamic_node_id_client.hpp>
#include <uavcan/equipment/esc/Status.hpp>
#include <uavcan/equipment/esc/RawCommand.hpp>

View File

@ -17,7 +17,7 @@
#include "AP_CANDriver.h"
#include <AP_HAL/Semaphores.h>
#include <AP_UAVCAN/AP_UAVCAN.h>
#include <AP_DroneCAN/AP_DroneCAN.h>
#ifndef HAL_ENABLE_CANTESTER
#define HAL_ENABLE_CANTESTER 0
#endif