ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSer...

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

57 lines
1.7 KiB
C
Raw Permalink Normal View History

#pragma once
#include "AP_RangeFinder_config.h"
#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED
#include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend_Serial.h"
class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend_Serial
{
public:
static AP_RangeFinder_Backend_Serial *create(
RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params) {
return NEW_NOTHROW AP_RangeFinder_LightWareSerial(_state, _params);
}
protected:
using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial;
MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
return MAV_DISTANCE_SENSOR_LASER;
}
int8_t get_signal_quality_pct() const override {
return no_signal ? RangeFinder::SIGNAL_QUALITY_MIN : RangeFinder::SIGNAL_QUALITY_MAX;
}
private:
// get a reading
bool get_reading(float &reading_m) override;
bool is_lost_signal_distance(int16_t distance_cm, int16_t distance_cm_max);
char linebuf[10]; // legacy protocol buffer
uint8_t linebuf_len; // legacy protocol buffer length
uint32_t last_init_ms; // init time used to switch lw20 to serial mode
uint8_t high_byte; // binary protocol high byte
bool high_byte_received; // true if high byte has been received
// automatic protocol decision variables
enum class ProtocolState {
UNKNOWN, // the protocol used is not yet known
LEGACY, // legacy protocol, distances are sent as strings
BINARY // binary protocol, distances are sent using two bytes
} protocol_state;
uint8_t legacy_valid_count;
uint8_t binary_valid_count;
bool no_signal = false;
};
#endif // AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED