2023-04-08 00:53:24 -03:00
|
|
|
#pragma once
|
|
|
|
|
2023-06-09 02:58:29 -03:00
|
|
|
#include "AP_Airspeed_config.h"
|
2023-04-08 00:53:24 -03:00
|
|
|
|
2023-04-08 00:58:12 -03:00
|
|
|
#if AP_AIRSPEED_DRONECAN_ENABLED
|
2023-04-08 00:53:24 -03:00
|
|
|
|
|
|
|
#include "AP_Airspeed_Backend.h"
|
|
|
|
|
|
|
|
#include <AP_DroneCAN/AP_DroneCAN.h>
|
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
class AP_Airspeed_DroneCAN : public AP_Airspeed_Backend {
|
2023-04-08 00:53:24 -03:00
|
|
|
public:
|
2022-07-31 22:02:23 -03:00
|
|
|
|
|
|
|
using AP_Airspeed_Backend::AP_Airspeed_Backend;
|
2023-04-08 00:53:24 -03:00
|
|
|
|
|
|
|
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);
|
|
|
|
|
2023-06-21 04:24:24 -03:00
|
|
|
static AP_Airspeed_Backend* probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid);
|
2023-04-08 00:53:24 -03:00
|
|
|
|
|
|
|
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);
|
|
|
|
|
2023-04-08 01:27:51 -03:00
|
|
|
static AP_Airspeed_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id);
|
2023-04-08 00:53:24 -03:00
|
|
|
|
|
|
|
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;
|
2023-04-08 01:09:10 -03:00
|
|
|
AP_Airspeed_DroneCAN *driver;
|
2023-04-08 00:53:24 -03:00
|
|
|
} _detected_modules[AIRSPEED_MAX_SENSORS];
|
|
|
|
|
|
|
|
static HAL_Semaphore _sem_registry;
|
|
|
|
bool _have_temperature;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
2023-04-08 00:58:12 -03:00
|
|
|
#endif // AP_AIRSPEED_DRONECAN_ENABLED
|