AP_RangeFinder: rename more variables, types and defines

This commit is contained in:
Andrew Tridgell 2023-04-08 14:09:10 +10:00
parent 70b04a22f0
commit 83114f4c74
3 changed files with 13 additions and 13 deletions

View File

@ -57,7 +57,7 @@ class RangeFinder
{
friend class AP_RangeFinder_Backend;
//UAVCAN drivers are initialised in the Backend, hence list of drivers is needed there.
friend class AP_RangeFinder_UAVCAN;
friend class AP_RangeFinder_DroneCAN;
public:
RangeFinder();

View File

@ -13,7 +13,7 @@ extern const AP_HAL::HAL& hal;
#define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0)
//links the rangefinder uavcan message to this backend
void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
void AP_RangeFinder_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
{
if (ap_dronecan == nullptr) {
return;
@ -24,18 +24,18 @@ void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
}
//Method to find the backend relating to the node id
AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new)
AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new)
{
if (ap_dronecan == nullptr) {
return nullptr;
}
AP_RangeFinder_UAVCAN* driver = nullptr;
AP_RangeFinder_DroneCAN* driver = nullptr;
RangeFinder &frontend = *AP::rangefinder();
//Scan through the Rangefinder params to find UAVCAN RFND with matching address.
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
if ((RangeFinder::Type)frontend.params[i].type.get() == RangeFinder::Type::UAVCAN &&
frontend.params[i].address == address) {
driver = (AP_RangeFinder_UAVCAN*)frontend.drivers[i];
driver = (AP_RangeFinder_DroneCAN*)frontend.drivers[i];
}
//Double check if the driver was initialised as UAVCAN Type
if (driver != nullptr && (driver->_backend_type == RangeFinder::Type::UAVCAN)) {
@ -60,8 +60,8 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap
//it up as UAVCAN type
return nullptr;
}
frontend.drivers[i] = new AP_RangeFinder_UAVCAN(frontend.state[i], frontend.params[i]);
driver = (AP_RangeFinder_UAVCAN*)frontend.drivers[i];
frontend.drivers[i] = new AP_RangeFinder_DroneCAN(frontend.state[i], frontend.params[i]);
driver = (AP_RangeFinder_DroneCAN*)frontend.drivers[i];
if (driver == nullptr) {
break;
}
@ -81,7 +81,7 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap
}
//Called from frontend to update with the readings received by handler
void AP_RangeFinder_UAVCAN::update()
void AP_RangeFinder_DroneCAN::update()
{
WITH_SEMAPHORE(_sem);
if ((AP_HAL::millis() - _last_reading_ms) > 500) {
@ -100,10 +100,10 @@ void AP_RangeFinder_UAVCAN::update()
}
//RangeFinder message handler
void AP_RangeFinder_UAVCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg)
void AP_RangeFinder_DroneCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg)
{
//fetch the matching uavcan driver, node id and sensor id backend instance
AP_RangeFinder_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true);
AP_RangeFinder_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true);
if (driver == nullptr) {
return;
}

View File

@ -3,7 +3,7 @@
#include "AP_RangeFinder_Backend.h"
#ifndef AP_RANGEFINDER_DRONECAN_ENABLED
#define AP_RANGEFINDER_DRONECAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#define AP_RANGEFINDER_DRONECAN_ENABLED (HAL_ENABLE_DRONECAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#endif
#if AP_RANGEFINDER_DRONECAN_ENABLED
@ -12,7 +12,7 @@
class MeasurementCb;
class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend {
class AP_RangeFinder_DroneCAN : public AP_RangeFinder_Backend {
public:
//constructor - registers instance at top RangeFinder driver
using AP_RangeFinder_Backend::AP_RangeFinder_Backend;
@ -20,7 +20,7 @@ public:
void update() override;
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
static AP_RangeFinder_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new);
static AP_RangeFinder_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new);
static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg);