2020-08-04 17:42:19 -03:00
|
|
|
#pragma once
|
|
|
|
|
2023-07-06 01:25:14 -03:00
|
|
|
#include "AP_RangeFinder_config.h"
|
2020-08-04 17:42:19 -03:00
|
|
|
|
2020-09-01 04:54:29 -03:00
|
|
|
#if HAL_MSP_RANGEFINDER_ENABLED
|
2020-08-04 17:42:19 -03:00
|
|
|
|
2023-07-06 01:25:14 -03:00
|
|
|
#include "AP_RangeFinder.h"
|
|
|
|
#include "AP_RangeFinder_Backend.h"
|
|
|
|
|
2020-08-04 17:42:19 -03:00
|
|
|
// Data timeout
|
|
|
|
#define AP_RANGEFINDER_MSP_TIMEOUT_MS 500
|
|
|
|
|
|
|
|
class AP_RangeFinder_MSP : public AP_RangeFinder_Backend
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
// constructor
|
|
|
|
AP_RangeFinder_MSP(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
|
|
|
|
|
|
|
|
// static detection function
|
|
|
|
static bool detect();
|
|
|
|
|
|
|
|
// update state
|
|
|
|
void update(void) override;
|
|
|
|
|
|
|
|
// Get update from msp
|
2020-09-07 19:29:23 -03:00
|
|
|
void handle_msp(const MSP::msp_rangefinder_data_message_t &pkt) override;
|
2020-08-04 17:42:19 -03:00
|
|
|
|
|
|
|
protected:
|
|
|
|
|
|
|
|
MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
|
|
|
|
return MAV_DISTANCE_SENSOR_UNKNOWN;
|
|
|
|
}
|
|
|
|
|
|
|
|
private:
|
|
|
|
uint16_t distance_cm;
|
|
|
|
|
|
|
|
// start a reading
|
|
|
|
static bool start_reading(void);
|
|
|
|
static bool get_reading(uint16_t &reading_cm);
|
|
|
|
};
|
|
|
|
|
2020-09-01 04:54:29 -03:00
|
|
|
#endif //HAL_MSP_RANGEFINDER_ENABLED
|
|
|
|
|