ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

56 lines
1.2 KiB
C
Raw Normal View History

2016-05-04 00:02:44 -03:00
#pragma once
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_MAVLINK_ENABLED
#include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.h"
2016-05-04 00:02:44 -03:00
// Data timeout
#define AP_RANGEFINDER_MAVLINK_TIMEOUT_MS 500
2016-05-04 00:02:44 -03:00
class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend
2016-05-04 00:02:44 -03:00
{
public:
2016-05-04 00:02:44 -03:00
// constructor
using AP_RangeFinder_Backend::AP_RangeFinder_Backend;
2016-05-04 00:02:44 -03:00
// Assume that if the user set the RANGEFINDER_TYPE parameter to MAVLink,
// there is an attached MAVLink rangefinder
static bool detect() { return true; }
2016-05-04 00:02:44 -03:00
// update state
void update(void) override;
2016-05-04 00:02:44 -03:00
// Get update from mavlink
void handle_msg(const mavlink_message_t &msg) override;
2016-05-04 00:02:44 -03:00
int16_t max_distance_cm() const override;
int16_t min_distance_cm() const override;
protected:
MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
return sensor_type;
}
2016-05-04 00:02:44 -03:00
private:
// stored data from packet:
uint16_t distance_cm;
uint16_t _max_distance_cm;
uint16_t _min_distance_cm;
int8_t signal_quality;
2016-05-04 00:02:44 -03:00
// start a reading
static bool start_reading(void);
static bool get_reading(uint16_t &reading_cm);
MAV_DISTANCE_SENSOR sensor_type = MAV_DISTANCE_SENSOR_UNKNOWN;
2016-05-04 00:02:44 -03:00
};
#endif