ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h
Thomas Watson fbeab64be2 AP_RangeFinder: optimize DroneCAN subscription process
* remove unnecessary nullptr check, these are always called from an
  initialized AP_DroneCAN so if it's nullptr something has gone
  horrifically wrong

* pass in driver index instead of repeatedly calling function to get it

* simplify error handling; knowing exactly which allocation failed is not
  super helpful and one failing likely means subsequent ones will too,
  as it can only fail due to being out of memory
2024-11-18 10:30:29 +11:00

40 lines
1.2 KiB
C++

#pragma once
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_DRONECAN_ENABLED
#include "AP_RangeFinder_Backend.h"
#include <AP_DroneCAN/AP_DroneCAN.h>
class MeasurementCb;
class AP_RangeFinder_DroneCAN : public AP_RangeFinder_Backend {
public:
//constructor - registers instance at top RangeFinder driver
using AP_RangeFinder_Backend::AP_RangeFinder_Backend;
void update() override;
static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
static AP_RangeFinder_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, 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_DroneCAN *ap_dronecan, 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_DroneCAN* _ap_dronecan;
uint8_t _node_id;
bool new_data;
MAV_DISTANCE_SENSOR _sensor_type;
};
#endif // AP_RANGEFINDER_DRONECAN_ENABLED