mirror of https://github.com/ArduPilot/ardupilot
43 lines
1.3 KiB
C++
43 lines
1.3 KiB
C++
#pragma once
|
|
|
|
#include "AP_RangeFinder_Backend.h"
|
|
|
|
#ifndef AP_RANGEFINDER_UAVCAN_ENABLED
|
|
#define AP_RANGEFINDER_UAVCAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
|
#endif
|
|
|
|
#if AP_RANGEFINDER_UAVCAN_ENABLED
|
|
|
|
#include <AP_UAVCAN/AP_UAVCAN.h>
|
|
|
|
class MeasurementCb;
|
|
|
|
class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend {
|
|
public:
|
|
//constructor - registers instance at top RangeFinder driver
|
|
using AP_RangeFinder_Backend::AP_RangeFinder_Backend;
|
|
|
|
void update() override;
|
|
|
|
static void subscribe_msgs(AP_UAVCAN* ap_uavcan);
|
|
static AP_RangeFinder_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, 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_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg);
|
|
|
|
protected:
|
|
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
|
|
return _sensor_type;
|
|
}
|
|
private:
|
|
uint8_t _instance;
|
|
RangeFinder::Status _status;
|
|
uint16_t _distance_cm;
|
|
uint32_t _last_reading_ms;
|
|
AP_UAVCAN* _ap_uavcan;
|
|
uint8_t _node_id;
|
|
bool new_data;
|
|
MAV_DISTANCE_SENSOR _sensor_type;
|
|
};
|
|
#endif // AP_RANGEFINDER_UAVCAN_ENABLED
|