AP_Baro: rename AP_UAVCAN to AP_DroneCAN

This commit is contained in:
Andrew Tridgell 2023-04-07 10:18:01 +10:00
parent 85ce16deb6
commit 305a8275f8
2 changed files with 26 additions and 26 deletions

View File

@ -21,16 +21,16 @@ AP_Baro_UAVCAN::AP_Baro_UAVCAN(AP_Baro &baro) :
AP_Baro_Backend(baro)
{}
void AP_Baro_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan)
void AP_Baro_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
{
if (ap_uavcan == nullptr) {
if (ap_dronecan == nullptr) {
return;
}
if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_pressure, ap_uavcan->get_driver_index()) == nullptr) {
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, ap_dronecan->get_driver_index()) == nullptr) {
AP_BoardConfig::allocation_error("pressure_sub");
}
if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_temperature, ap_uavcan->get_driver_index()) == nullptr) {
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, ap_dronecan->get_driver_index()) == nullptr) {
AP_BoardConfig::allocation_error("temperature_sub");
}
}
@ -41,31 +41,31 @@ AP_Baro_Backend* AP_Baro_UAVCAN::probe(AP_Baro &baro)
AP_Baro_UAVCAN* backend = nullptr;
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) {
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) {
backend = new AP_Baro_UAVCAN(baro);
if (backend == nullptr) {
AP::can().log_text(AP_CANManager::LOG_ERROR,
LOG_TAG,
"Failed register UAVCAN Baro Node %d on Bus %d\n",
_detected_modules[i].node_id,
_detected_modules[i].ap_uavcan->get_driver_index());
_detected_modules[i].ap_dronecan->get_driver_index());
} else {
_detected_modules[i].driver = backend;
backend->_pressure = 0;
backend->_pressure_count = 0;
backend->_ap_uavcan = _detected_modules[i].ap_uavcan;
backend->_ap_dronecan = _detected_modules[i].ap_dronecan;
backend->_node_id = _detected_modules[i].node_id;
backend->_instance = backend->_frontend.register_sensor();
backend->set_bus_id(backend->_instance, AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN,
_detected_modules[i].ap_uavcan->get_driver_index(),
_detected_modules[i].ap_dronecan->get_driver_index(),
backend->_node_id, 0));
AP::can().log_text(AP_CANManager::LOG_INFO,
LOG_TAG,
"Registered UAVCAN Baro Node %d on Bus %d\n",
_detected_modules[i].node_id,
_detected_modules[i].ap_uavcan->get_driver_index());
_detected_modules[i].ap_dronecan->get_driver_index());
}
break;
}
@ -73,14 +73,14 @@ AP_Baro_Backend* AP_Baro_UAVCAN::probe(AP_Baro &baro)
return backend;
}
AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, bool create_new)
AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new)
{
if (ap_uavcan == nullptr) {
if (ap_dronecan == nullptr) {
return nullptr;
}
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
if (_detected_modules[i].driver != nullptr &&
_detected_modules[i].ap_uavcan == ap_uavcan &&
_detected_modules[i].ap_dronecan == ap_dronecan &&
_detected_modules[i].node_id == node_id) {
return _detected_modules[i].driver;
}
@ -90,7 +90,7 @@ AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t
bool already_detected = false;
//Check if there's an empty spot for possible registeration
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
if (_detected_modules[i].ap_uavcan == ap_uavcan && _detected_modules[i].node_id == node_id) {
if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) {
//Already Detected
already_detected = true;
break;
@ -98,8 +98,8 @@ AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t
}
if (!already_detected) {
for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) {
if (_detected_modules[i].ap_uavcan == nullptr) {
_detected_modules[i].ap_uavcan = ap_uavcan;
if (_detected_modules[i].ap_dronecan == nullptr) {
_detected_modules[i].ap_dronecan = ap_dronecan;
_detected_modules[i].node_id = node_id;
break;
}
@ -121,12 +121,12 @@ void AP_Baro_UAVCAN::_update_and_wrap_accumulator(float *accum, float val, uint8
}
}
void AP_Baro_UAVCAN::handle_pressure(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg)
void AP_Baro_UAVCAN::handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg)
{
AP_Baro_UAVCAN* driver;
{
WITH_SEMAPHORE(_sem_registry);
driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, true);
driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, true);
if (driver == nullptr) {
return;
}
@ -138,12 +138,12 @@ void AP_Baro_UAVCAN::handle_pressure(AP_UAVCAN *ap_uavcan, const CanardRxTransfe
}
}
void AP_Baro_UAVCAN::handle_temperature(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg)
void AP_Baro_UAVCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg)
{
AP_Baro_UAVCAN* driver;
{
WITH_SEMAPHORE(_sem_registry);
driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, false);
driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, false);
if (driver == nullptr) {
return;
}

View File

@ -4,7 +4,7 @@
#if AP_BARO_UAVCAN_ENABLED
#include <AP_UAVCAN/AP_UAVCAN.h>
#include <AP_DroneCAN/AP_DroneCAN.h>
#if AP_TEST_DRONECAN_DRIVERS
#include <SITL/SITL.h>
#endif
@ -15,12 +15,12 @@ public:
void update() override;
static void subscribe_msgs(AP_UAVCAN* ap_uavcan);
static AP_Baro_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, bool create_new);
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
static AP_Baro_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new);
static AP_Baro_Backend* probe(AP_Baro &baro);
static void handle_pressure(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg);
static void handle_temperature(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg);
static void handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg);
static void handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg);
#if AP_TEST_DRONECAN_DRIVERS
void update_healthy_flag(uint8_t instance) override { _frontend.sensors[instance].healthy = !AP::sitl()->baro[instance].disable; };
#endif
@ -36,12 +36,12 @@ private:
uint8_t _pressure_count;
HAL_Semaphore _sem_baro;
AP_UAVCAN* _ap_uavcan;
AP_DroneCAN* _ap_dronecan;
uint8_t _node_id;
// Module Detection Registry
static struct DetectedModules {
AP_UAVCAN* ap_uavcan;
AP_DroneCAN* ap_dronecan;
uint8_t node_id;
AP_Baro_UAVCAN* driver;
} _detected_modules[BARO_MAX_DRIVERS];