From 9489ec9e7c3695290210b140d49ddab72d7b7a45 Mon Sep 17 00:00:00 2001 From: Francisco Ferreira Date: Wed, 18 Jul 2018 07:27:37 +0100 Subject: [PATCH] AP_Baro: adapt to changes in AP_BoardConfig_CAN --- libraries/AP_Baro/AP_Baro_UAVCAN.cpp | 32 ++++++++++------------------ 1 file changed, 11 insertions(+), 21 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp b/libraries/AP_Baro/AP_Baro_UAVCAN.cpp index eb6bc5fa9c..b976006e5a 100644 --- a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_UAVCAN.cpp @@ -3,19 +3,12 @@ #if HAL_WITH_UAVCAN #include "AP_Baro_UAVCAN.h" -#include -#include -#if HAL_OS_POSIX_IO -#include -#include -#include -#include -#endif +#include extern const AP_HAL::HAL& hal; -#define debug_baro_uavcan(level, fmt, args...) do { if ((level) <= AP_BoardConfig_CAN::get_can_debug()) { printf(fmt, ##args); }} while (0) +#define debug_baro_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { printf(fmt, ##args); }} while (0) /* constructor - registers instance at top Baro driver @@ -31,39 +24,36 @@ AP_Baro_UAVCAN::~AP_Baro_UAVCAN() if (!_initialized) { return; } - + AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(_manager); if (ap_uavcan == nullptr) { return; } - + ap_uavcan->remove_baro_listener(this); delete _sem_baro; - - debug_baro_uavcan(2, "AP_Baro_UAVCAN destructed\n\r"); + + debug_baro_uavcan(2, _manager, "AP_Baro_UAVCAN destructed\n\r"); } AP_Baro_Backend *AP_Baro_UAVCAN::probe(AP_Baro &baro) { - - if (AP_BoardConfig_CAN::get_can_num_ifaces() == 0) { - return nullptr; - } + uint8_t can_num_drivers = AP::can().get_num_drivers(); AP_Baro_UAVCAN *sensor; - for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) { + for (uint8_t i = 0; i < can_num_drivers; i++) { AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i); if (ap_uavcan == nullptr) { continue; } - + uint8_t freebaro = ap_uavcan->find_smallest_free_baro_node(); if (freebaro == UINT8_MAX) { continue; } sensor = new AP_Baro_UAVCAN(baro); if (sensor->register_uavcan_baro(i, freebaro)) { - debug_baro_uavcan(2, "AP_Baro_UAVCAN probed, drv: %d, node: %d\n\r", i, freebaro); + debug_baro_uavcan(2, i, "AP_Baro_UAVCAN probed, drv: %d, node: %d\n\r", i, freebaro); return sensor; } else { delete sensor; @@ -104,7 +94,7 @@ bool AP_Baro_UAVCAN::register_uavcan_baro(uint8_t mgr, uint8_t node) if (ap_uavcan->register_baro_listener_to_node(this, node)) { _instance = _frontend.register_sensor(); - debug_baro_uavcan(2, "AP_Baro_UAVCAN loaded\n\r"); + debug_baro_uavcan(2, mgr, "AP_Baro_UAVCAN loaded\n\r"); _initialized = true;