mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Airspeed: rename more variables, types and defines
This commit is contained in:
parent
b322a7a1fe
commit
6912b0db9e
@ -416,7 +416,7 @@ void AP_Airspeed::allocate()
|
||||
break;
|
||||
case TYPE_UAVCAN:
|
||||
#if AP_AIRSPEED_DRONECAN_ENABLED
|
||||
sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i, uint32_t(param[i].bus_id.get()));
|
||||
sensor[i] = AP_Airspeed_DroneCAN::probe(*this, i, uint32_t(param[i].bus_id.get()));
|
||||
#endif
|
||||
break;
|
||||
case TYPE_NMEA_WATER:
|
||||
@ -447,7 +447,7 @@ void AP_Airspeed::allocate()
|
||||
// the 2nd pass accepts any devid
|
||||
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
|
||||
if (sensor[i] == nullptr && (enum airspeed_type)param[i].type.get() == TYPE_UAVCAN) {
|
||||
sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i, 0);
|
||||
sensor[i] = AP_Airspeed_DroneCAN::probe(*this, i, 0);
|
||||
if (sensor[i] != nullptr) {
|
||||
num_sensors = i+1;
|
||||
}
|
||||
|
@ -10,15 +10,15 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define LOG_TAG "AirSpeed"
|
||||
|
||||
AP_Airspeed_UAVCAN::DetectedModules AP_Airspeed_UAVCAN::_detected_modules[];
|
||||
HAL_Semaphore AP_Airspeed_UAVCAN::_sem_registry;
|
||||
AP_Airspeed_DroneCAN::DetectedModules AP_Airspeed_DroneCAN::_detected_modules[];
|
||||
HAL_Semaphore AP_Airspeed_DroneCAN::_sem_registry;
|
||||
|
||||
// constructor
|
||||
AP_Airspeed_UAVCAN::AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance) :
|
||||
AP_Airspeed_DroneCAN::AP_Airspeed_DroneCAN(AP_Airspeed &_frontend, uint8_t _instance) :
|
||||
AP_Airspeed_Backend(_frontend, _instance)
|
||||
{}
|
||||
|
||||
void AP_Airspeed_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
void AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
{
|
||||
if (ap_dronecan == nullptr) {
|
||||
return;
|
||||
@ -35,11 +35,11 @@ void AP_Airspeed_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
#endif
|
||||
}
|
||||
|
||||
AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid)
|
||||
AP_Airspeed_Backend* AP_Airspeed_DroneCAN::probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid)
|
||||
{
|
||||
WITH_SEMAPHORE(_sem_registry);
|
||||
|
||||
AP_Airspeed_UAVCAN* backend = nullptr;
|
||||
AP_Airspeed_DroneCAN* backend = nullptr;
|
||||
|
||||
for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) {
|
||||
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) {
|
||||
@ -50,7 +50,7 @@ AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _
|
||||
// match with previous ID only
|
||||
continue;
|
||||
}
|
||||
backend = new AP_Airspeed_UAVCAN(_frontend, _instance);
|
||||
backend = new AP_Airspeed_DroneCAN(_frontend, _instance);
|
||||
if (backend == nullptr) {
|
||||
AP::can().log_text(AP_CANManager::LOG_INFO,
|
||||
LOG_TAG,
|
||||
@ -73,7 +73,7 @@ AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _
|
||||
return backend;
|
||||
}
|
||||
|
||||
AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id)
|
||||
AP_Airspeed_DroneCAN* AP_Airspeed_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id)
|
||||
{
|
||||
if (ap_dronecan == nullptr) {
|
||||
return nullptr;
|
||||
@ -109,11 +109,11 @@ AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_drone
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void AP_Airspeed_UAVCAN::handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg)
|
||||
void AP_Airspeed_DroneCAN::handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg)
|
||||
{
|
||||
WITH_SEMAPHORE(_sem_registry);
|
||||
|
||||
AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id);
|
||||
AP_Airspeed_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id);
|
||||
|
||||
if (driver != nullptr) {
|
||||
WITH_SEMAPHORE(driver->_sem_airspeed);
|
||||
@ -128,11 +128,11 @@ void AP_Airspeed_UAVCAN::handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardR
|
||||
}
|
||||
|
||||
#if AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
void AP_Airspeed_UAVCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg)
|
||||
void AP_Airspeed_DroneCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg)
|
||||
{
|
||||
WITH_SEMAPHORE(_sem_registry);
|
||||
|
||||
AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id);
|
||||
AP_Airspeed_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id);
|
||||
|
||||
if (driver != nullptr) {
|
||||
WITH_SEMAPHORE(driver->_sem_airspeed);
|
||||
@ -143,13 +143,13 @@ void AP_Airspeed_UAVCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const Canar
|
||||
}
|
||||
#endif // AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
|
||||
bool AP_Airspeed_UAVCAN::init()
|
||||
bool AP_Airspeed_DroneCAN::init()
|
||||
{
|
||||
// always returns true
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_Airspeed_UAVCAN::get_differential_pressure(float &pressure)
|
||||
bool AP_Airspeed_DroneCAN::get_differential_pressure(float &pressure)
|
||||
{
|
||||
WITH_SEMAPHORE(_sem_airspeed);
|
||||
|
||||
@ -162,7 +162,7 @@ bool AP_Airspeed_UAVCAN::get_differential_pressure(float &pressure)
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_Airspeed_UAVCAN::get_temperature(float &temperature)
|
||||
bool AP_Airspeed_DroneCAN::get_temperature(float &temperature)
|
||||
{
|
||||
if (!_have_temperature) {
|
||||
return false;
|
||||
@ -182,7 +182,7 @@ bool AP_Airspeed_UAVCAN::get_temperature(float &temperature)
|
||||
/*
|
||||
return hygrometer data if available
|
||||
*/
|
||||
bool AP_Airspeed_UAVCAN::get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity)
|
||||
bool AP_Airspeed_DroneCAN::get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity)
|
||||
{
|
||||
if (_hygrometer.last_sample_ms == 0) {
|
||||
return false;
|
||||
|
@ -3,7 +3,7 @@
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_DRONECAN_ENABLED
|
||||
#define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
#define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_DRONECAN_DRIVERS
|
||||
#endif
|
||||
|
||||
#if AP_AIRSPEED_DRONECAN_ENABLED
|
||||
@ -12,9 +12,9 @@
|
||||
|
||||
#include <AP_DroneCAN/AP_DroneCAN.h>
|
||||
|
||||
class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend {
|
||||
class AP_Airspeed_DroneCAN : public AP_Airspeed_Backend {
|
||||
public:
|
||||
AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance);
|
||||
AP_Airspeed_DroneCAN(AP_Airspeed &_frontend, uint8_t _instance);
|
||||
|
||||
bool init(void) override;
|
||||
|
||||
@ -38,7 +38,7 @@ private:
|
||||
static void handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg);
|
||||
static void handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg);
|
||||
|
||||
static AP_Airspeed_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id);
|
||||
static AP_Airspeed_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id);
|
||||
|
||||
float _pressure; // Pascal
|
||||
float _temperature; // Celcius
|
||||
@ -57,7 +57,7 @@ private:
|
||||
static struct DetectedModules {
|
||||
AP_DroneCAN* ap_dronecan;
|
||||
uint8_t node_id;
|
||||
AP_Airspeed_UAVCAN *driver;
|
||||
AP_Airspeed_DroneCAN *driver;
|
||||
} _detected_modules[AIRSPEED_MAX_SENSORS];
|
||||
|
||||
static HAL_Semaphore _sem_registry;
|
||||
|
Loading…
Reference in New Issue
Block a user