mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: rename UAVCAN drivers to DroneCAN
This commit is contained in:
parent
9371e60431
commit
a3d0f265b2
|
@ -0,0 +1,197 @@
|
|||
#include "AP_Airspeed_UAVCAN.h"
|
||||
|
||||
#if AP_AIRSPEED_UAVCAN_ENABLED
|
||||
|
||||
#include <AP_CANManager/AP_CANManager.h>
|
||||
#include <AP_DroneCAN/AP_DroneCAN.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
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;
|
||||
|
||||
// constructor
|
||||
AP_Airspeed_UAVCAN::AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance) :
|
||||
AP_Airspeed_Backend(_frontend, _instance)
|
||||
{}
|
||||
|
||||
void AP_Airspeed_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
{
|
||||
if (ap_dronecan == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("airspeed_sub");
|
||||
}
|
||||
|
||||
#if AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("hygrometer_sub");
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid)
|
||||
{
|
||||
WITH_SEMAPHORE(_sem_registry);
|
||||
|
||||
AP_Airspeed_UAVCAN* backend = nullptr;
|
||||
|
||||
for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) {
|
||||
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) {
|
||||
const auto bus_id = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN,
|
||||
_detected_modules[i].ap_dronecan->get_driver_index(),
|
||||
_detected_modules[i].node_id, 0);
|
||||
if (previous_devid != 0 && previous_devid != bus_id) {
|
||||
// match with previous ID only
|
||||
continue;
|
||||
}
|
||||
backend = new AP_Airspeed_UAVCAN(_frontend, _instance);
|
||||
if (backend == nullptr) {
|
||||
AP::can().log_text(AP_CANManager::LOG_INFO,
|
||||
LOG_TAG,
|
||||
"Failed register UAVCAN Airspeed Node %d on Bus %d\n",
|
||||
_detected_modules[i].node_id,
|
||||
_detected_modules[i].ap_dronecan->get_driver_index());
|
||||
} else {
|
||||
_detected_modules[i].driver = backend;
|
||||
AP::can().log_text(AP_CANManager::LOG_INFO,
|
||||
LOG_TAG,
|
||||
"Registered UAVCAN Airspeed Node %d on Bus %d\n",
|
||||
_detected_modules[i].node_id,
|
||||
_detected_modules[i].ap_dronecan->get_driver_index());
|
||||
backend->set_bus_id(bus_id);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return backend;
|
||||
}
|
||||
|
||||
AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id)
|
||||
{
|
||||
if (ap_dronecan == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) {
|
||||
if (_detected_modules[i].driver != nullptr &&
|
||||
_detected_modules[i].ap_dronecan == ap_dronecan &&
|
||||
_detected_modules[i].node_id == node_id ) {
|
||||
return _detected_modules[i].driver;
|
||||
}
|
||||
}
|
||||
|
||||
bool detected = false;
|
||||
for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) {
|
||||
if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) {
|
||||
// detected
|
||||
detected = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (!detected) {
|
||||
for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) {
|
||||
if (_detected_modules[i].ap_dronecan == nullptr) {
|
||||
_detected_modules[i].ap_dronecan = ap_dronecan;
|
||||
_detected_modules[i].node_id = node_id;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void AP_Airspeed_UAVCAN::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);
|
||||
|
||||
if (driver != nullptr) {
|
||||
WITH_SEMAPHORE(driver->_sem_airspeed);
|
||||
driver->_pressure = msg.differential_pressure;
|
||||
if (!isnan(msg.static_air_temperature) &&
|
||||
msg.static_air_temperature > 0) {
|
||||
driver->_temperature = KELVIN_TO_C(msg.static_air_temperature);
|
||||
driver->_have_temperature = true;
|
||||
}
|
||||
driver->_last_sample_time_ms = AP_HAL::millis();
|
||||
}
|
||||
}
|
||||
|
||||
#if AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
void AP_Airspeed_UAVCAN::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);
|
||||
|
||||
if (driver != nullptr) {
|
||||
WITH_SEMAPHORE(driver->_sem_airspeed);
|
||||
driver->_hygrometer.temperature = KELVIN_TO_C(msg.temperature);
|
||||
driver->_hygrometer.humidity = msg.humidity;
|
||||
driver->_hygrometer.last_sample_ms = AP_HAL::millis();
|
||||
}
|
||||
}
|
||||
#endif // AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
|
||||
bool AP_Airspeed_UAVCAN::init()
|
||||
{
|
||||
// always returns true
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_Airspeed_UAVCAN::get_differential_pressure(float &pressure)
|
||||
{
|
||||
WITH_SEMAPHORE(_sem_airspeed);
|
||||
|
||||
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
||||
return false;
|
||||
}
|
||||
|
||||
pressure = _pressure;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_Airspeed_UAVCAN::get_temperature(float &temperature)
|
||||
{
|
||||
if (!_have_temperature) {
|
||||
return false;
|
||||
}
|
||||
WITH_SEMAPHORE(_sem_airspeed);
|
||||
|
||||
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
||||
return false;
|
||||
}
|
||||
|
||||
temperature = _temperature;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#if AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
/*
|
||||
return hygrometer data if available
|
||||
*/
|
||||
bool AP_Airspeed_UAVCAN::get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity)
|
||||
{
|
||||
if (_hygrometer.last_sample_ms == 0) {
|
||||
return false;
|
||||
}
|
||||
WITH_SEMAPHORE(_sem_airspeed);
|
||||
last_sample_ms = _hygrometer.last_sample_ms;
|
||||
temperature = _hygrometer.temperature;
|
||||
humidity = _hygrometer.humidity;
|
||||
return true;
|
||||
}
|
||||
#endif // AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
#endif // AP_AIRSPEED_UAVCAN_ENABLED
|
|
@ -0,0 +1,68 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_AIRSPEED_UAVCAN_ENABLED
|
||||
#define AP_AIRSPEED_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
#endif
|
||||
|
||||
#if AP_AIRSPEED_UAVCAN_ENABLED
|
||||
|
||||
#include "AP_Airspeed_Backend.h"
|
||||
|
||||
#include <AP_DroneCAN/AP_DroneCAN.h>
|
||||
|
||||
class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend {
|
||||
public:
|
||||
AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance);
|
||||
|
||||
bool init(void) override;
|
||||
|
||||
// return the current differential_pressure in Pascal
|
||||
bool get_differential_pressure(float &pressure) override;
|
||||
|
||||
// temperature not available via analog backend
|
||||
bool get_temperature(float &temperature) override;
|
||||
|
||||
#if AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
// get hygrometer data
|
||||
bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) override;
|
||||
#endif
|
||||
|
||||
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||
|
||||
static AP_Airspeed_Backend* probe(AP_Airspeed &_fronted, uint8_t _instance, uint32_t previous_devid);
|
||||
|
||||
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);
|
||||
|
||||
float _pressure; // Pascal
|
||||
float _temperature; // Celcius
|
||||
uint32_t _last_sample_time_ms;
|
||||
|
||||
// hygrometer data
|
||||
struct {
|
||||
float temperature;
|
||||
float humidity;
|
||||
uint32_t last_sample_ms;
|
||||
} _hygrometer;
|
||||
|
||||
HAL_Semaphore _sem_airspeed;
|
||||
|
||||
// Module Detection Registry
|
||||
static struct DetectedModules {
|
||||
AP_DroneCAN* ap_dronecan;
|
||||
uint8_t node_id;
|
||||
AP_Airspeed_UAVCAN *driver;
|
||||
} _detected_modules[AIRSPEED_MAX_SENSORS];
|
||||
|
||||
static HAL_Semaphore _sem_registry;
|
||||
bool _have_temperature;
|
||||
};
|
||||
|
||||
|
||||
#endif // AP_AIRSPEED_UAVCAN_ENABLED
|
Loading…
Reference in New Issue