AP_Compass: rename more variables, types and defines

This commit is contained in:
Andrew Tridgell 2023-04-08 14:09:10 +10:00
parent 33df480f87
commit e469ed9bd7
4 changed files with 25 additions and 25 deletions

View File

@ -1452,7 +1452,7 @@ void Compass::_detect_backends(void)
#if AP_COMPASS_DRONECAN_ENABLED
if (_driver_enabled(DRIVER_UAVCAN)) {
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
AP_Compass_Backend* _uavcan_backend = AP_Compass_UAVCAN::probe(i);
AP_Compass_Backend* _uavcan_backend = AP_Compass_DroneCAN::probe(i);
if (_uavcan_backend) {
_add_backend(_uavcan_backend);
}
@ -1474,7 +1474,7 @@ void Compass::_detect_backends(void)
// There's a UAVCAN compass missing
// Let's check if there's a replacement
for (uint8_t j=0; j<COMPASS_MAX_INSTANCES; j++) {
uint32_t detected_devid = AP_Compass_UAVCAN::get_detected_devid(j);
uint32_t detected_devid = AP_Compass_DroneCAN::get_detected_devid(j);
// Check if this is a potential replacement mag
if (!is_replacement_mag(detected_devid)) {
continue;
@ -1485,7 +1485,7 @@ void Compass::_detect_backends(void)
_priority_did_stored_list[i].set_and_save(0);
_priority_did_list[i] = 0;
AP_Compass_Backend* _uavcan_backend = AP_Compass_UAVCAN::probe(j);
AP_Compass_Backend* _uavcan_backend = AP_Compass_DroneCAN::probe(j);
if (_uavcan_backend) {
_add_backend(_uavcan_backend);
// we also need to remove the id from unreg list
@ -1625,7 +1625,7 @@ Compass::_detect_runtime(void)
last_try = AP_HAL::millis();
if (_driver_enabled(DRIVER_UAVCAN)) {
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
AP_Compass_Backend* _uavcan_backend = AP_Compass_UAVCAN::probe(i);
AP_Compass_Backend* _uavcan_backend = AP_Compass_DroneCAN::probe(i);
if (_uavcan_backend) {
_add_backend(_uavcan_backend);
}

View File

@ -28,10 +28,10 @@ extern const AP_HAL::HAL& hal;
#define LOG_TAG "COMPASS"
AP_Compass_UAVCAN::DetectedModules AP_Compass_UAVCAN::_detected_modules[];
HAL_Semaphore AP_Compass_UAVCAN::_sem_registry;
AP_Compass_DroneCAN::DetectedModules AP_Compass_DroneCAN::_detected_modules[];
HAL_Semaphore AP_Compass_DroneCAN::_sem_registry;
AP_Compass_UAVCAN::AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid)
AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid)
: _ap_dronecan(ap_dronecan)
, _node_id(node_id)
, _sensor_id(sensor_id)
@ -39,7 +39,7 @@ AP_Compass_UAVCAN::AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id,
{
}
void AP_Compass_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
void AP_Compass_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
{
if (ap_dronecan == nullptr) {
return;
@ -53,13 +53,13 @@ void AP_Compass_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
}
}
AP_Compass_Backend* AP_Compass_UAVCAN::probe(uint8_t index)
AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index)
{
AP_Compass_UAVCAN* driver = nullptr;
AP_Compass_DroneCAN* driver = nullptr;
if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) {
WITH_SEMAPHORE(_sem_registry);
// Register new Compass mode to a backend
driver = new AP_Compass_UAVCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].node_id, _detected_modules[index].sensor_id, _detected_modules[index].devid);
driver = new AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].node_id, _detected_modules[index].sensor_id, _detected_modules[index].devid);
if (driver) {
if (!driver->init()) {
delete driver;
@ -94,7 +94,7 @@ AP_Compass_Backend* AP_Compass_UAVCAN::probe(uint8_t index)
return driver;
}
bool AP_Compass_UAVCAN::init()
bool AP_Compass_DroneCAN::init()
{
// Adding 1 is necessary to allow backward compatibilty, where this field was set as 1 by default
if (!register_compass(_devid, _instance)) {
@ -104,11 +104,11 @@ bool AP_Compass_UAVCAN::init()
set_dev_id(_instance, _devid);
set_external(_instance, true);
AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_UAVCAN loaded\n\r");
AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_DroneCAN loaded\n\r");
return true;
}
AP_Compass_UAVCAN* AP_Compass_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id)
AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id)
{
if (ap_dronecan == nullptr) {
return nullptr;
@ -165,19 +165,19 @@ AP_Compass_UAVCAN* AP_Compass_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_droneca
return nullptr;
}
void AP_Compass_UAVCAN::handle_mag_msg(const Vector3f &mag)
void AP_Compass_DroneCAN::handle_mag_msg(const Vector3f &mag)
{
Vector3f raw_field = mag * 1000.0;
accumulate_sample(raw_field, _instance);
}
void AP_Compass_UAVCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg)
void AP_Compass_DroneCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg)
{
WITH_SEMAPHORE(_sem_registry);
Vector3f mag_vector;
AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, 0);
AP_Compass_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, 0);
if (driver != nullptr) {
mag_vector[0] = msg.magnetic_field_ga[0];
mag_vector[1] = msg.magnetic_field_ga[1];
@ -186,13 +186,13 @@ void AP_Compass_UAVCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const Ca
}
}
void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg)
void AP_Compass_DroneCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg)
{
WITH_SEMAPHORE(_sem_registry);
Vector3f mag_vector;
uint8_t sensor_id = msg.sensor_id;
AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, sensor_id);
AP_Compass_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, sensor_id);
if (driver != nullptr) {
mag_vector[0] = msg.magnetic_field_ga[0];
mag_vector[1] = msg.magnetic_field_ga[1];
@ -201,7 +201,7 @@ void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const
}
}
void AP_Compass_UAVCAN::read(void)
void AP_Compass_DroneCAN::read(void)
{
drain_accumulated_samples(_instance);
}

View File

@ -8,9 +8,9 @@
#include <AP_DroneCAN/AP_DroneCAN.h>
class AP_Compass_UAVCAN : public AP_Compass_Backend {
class AP_Compass_DroneCAN : public AP_Compass_Backend {
public:
AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid);
AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid);
void read(void) override;
@ -26,7 +26,7 @@ private:
// callback for DroneCAN messages
void handle_mag_msg(const Vector3f &mag);
static AP_Compass_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id);
static AP_Compass_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id);
uint8_t _instance;
@ -40,7 +40,7 @@ private:
AP_DroneCAN* ap_dronecan;
uint8_t node_id;
uint8_t sensor_id;
AP_Compass_UAVCAN *driver;
AP_Compass_DroneCAN *driver;
uint32_t devid;
} _detected_modules[COMPASS_MAX_BACKEND];

View File

@ -26,7 +26,7 @@
#endif
#ifndef AP_COMPASS_DRONECAN_ENABLED
#define AP_COMPASS_DRONECAN_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS)
#define AP_COMPASS_DRONECAN_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS)
#endif
// i2c-based compasses: