2019-03-28 09:43:23 -03:00
|
|
|
#pragma once
|
|
|
|
|
2023-06-23 22:09:28 -03:00
|
|
|
#include "AP_RangeFinder_config.h"
|
2022-03-12 06:37:29 -04:00
|
|
|
|
|
|
|
#if AP_RANGEFINDER_BLPING_ENABLED
|
|
|
|
|
2019-11-10 22:47:38 -04:00
|
|
|
#include "AP_RangeFinder_Backend_Serial.h"
|
2019-03-28 09:43:23 -03:00
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
/**
|
|
|
|
* @brief Simple class to deal with Ping Protocol
|
|
|
|
*
|
|
|
|
* Protocol documentation can be found here: https:* github.com/bluerobotics/ping-protocol
|
|
|
|
*
|
|
|
|
* Byte Type Name Description
|
|
|
|
* --------------------------------------------------------------------------------------------------------------
|
|
|
|
* 0 uint8_t start1 'B'
|
|
|
|
* 1 uint8_t start2 'R'
|
|
|
|
* 2-3 uint16_t payload_length number of bytes in payload (low byte, high byte)
|
|
|
|
* 4-5 uint16_t message id message id (low byte, high byte)
|
|
|
|
* 6 uint8_t src_device_id id of device sending the message
|
|
|
|
* 7 uint8_t dst_device_id id of device of the intended recipient
|
|
|
|
* 8-n uint8_t[] payload message payload
|
|
|
|
* (n+1)-(n+2) uint16_t checksum the sum of all the non-checksum bytes in the message (low byte, high byte)
|
|
|
|
*/
|
|
|
|
class PingProtocol {
|
|
|
|
static constexpr uint8_t _frame_header1 = 0x42; // // header first byte ('B')
|
|
|
|
static constexpr uint8_t _frame_header2 = 0x52; // // header first byte ('R')
|
|
|
|
static constexpr uint16_t _src_id = 0; // vehicle's source id
|
|
|
|
static constexpr uint16_t _dst_id = 1; // sensor's id
|
2019-03-28 09:43:23 -03:00
|
|
|
|
|
|
|
public:
|
2020-01-28 14:41:25 -04:00
|
|
|
enum class MessageId {
|
|
|
|
INVALID = 0,
|
|
|
|
SET_PING_INTERVAL = 1004,
|
|
|
|
DISTANCE_SIMPLE = 1211,
|
|
|
|
CONTINUOUS_START = 1400,
|
|
|
|
};
|
2019-03-28 09:43:23 -03:00
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
/**
|
|
|
|
* @brief Process a single byte received on serial port
|
|
|
|
* return a valid MessageId if there is a message in buffer.
|
|
|
|
*
|
|
|
|
* @param byte
|
|
|
|
* @return MessageId
|
|
|
|
*/
|
|
|
|
MessageId parse_byte(uint8_t b);
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Send a message with a defined payload
|
|
|
|
*
|
|
|
|
* @param uart
|
|
|
|
* @param msgid
|
|
|
|
* @param payload
|
|
|
|
* @param payload_len
|
|
|
|
*/
|
|
|
|
void send_message(AP_HAL::UARTDriver *uart, PingProtocol::MessageId msg_id, const uint8_t *payload, uint16_t payload_len) const;
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Get distance from message
|
|
|
|
*
|
|
|
|
* @return uint32_t
|
|
|
|
*/
|
|
|
|
uint32_t get_distance_mm() const;
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Get confidence from message
|
|
|
|
*
|
|
|
|
* @return uint8_t
|
|
|
|
*/
|
|
|
|
uint8_t get_confidence() const;
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Get the message id available in bufffer
|
|
|
|
*
|
|
|
|
* @return MessageId
|
|
|
|
*/
|
|
|
|
MessageId get_message_id() const { return static_cast<MessageId>(msg.id); };
|
2019-03-28 09:43:23 -03:00
|
|
|
|
|
|
|
protected:
|
2020-01-28 14:41:25 -04:00
|
|
|
/**
|
|
|
|
* @brief State for the parser logic
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
enum class ParserState {
|
2019-03-28 09:43:23 -03:00
|
|
|
HEADER1 = 0,
|
|
|
|
HEADER2,
|
|
|
|
LEN_L,
|
|
|
|
LEN_H,
|
|
|
|
MSG_ID_L,
|
|
|
|
MSG_ID_H,
|
|
|
|
SRC_ID,
|
|
|
|
DST_ID,
|
|
|
|
PAYLOAD,
|
|
|
|
CRC_L,
|
|
|
|
CRC_H
|
|
|
|
};
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
/**
|
|
|
|
* @brief Structure holding the last message available with its state
|
|
|
|
*
|
|
|
|
*/
|
2019-03-28 09:43:23 -03:00
|
|
|
struct {
|
2020-01-28 14:41:25 -04:00
|
|
|
ParserState state; // state of incoming message processing
|
|
|
|
bool done; // inform if the message is complete or not
|
2019-03-28 09:43:23 -03:00
|
|
|
uint8_t payload[20]; // payload
|
|
|
|
uint16_t payload_len; // latest message payload length
|
2020-01-28 14:41:25 -04:00
|
|
|
uint16_t id; // latest message's message id
|
2019-03-28 09:43:23 -03:00
|
|
|
uint16_t payload_recv; // number of message's payload bytes received so far
|
|
|
|
uint16_t crc; // latest message's crc
|
|
|
|
uint16_t crc_expected; // latest message's expected crc
|
|
|
|
} msg;
|
|
|
|
};
|
2020-01-28 14:41:25 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Class for Blue Robotics Ping1D sensor
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
class AP_RangeFinder_BLPing : public AP_RangeFinder_Backend_Serial
|
|
|
|
{
|
|
|
|
static constexpr uint16_t _sensor_rate_ms = 50; // initialise sensor at no more than 20hz
|
|
|
|
|
|
|
|
public:
|
2022-06-22 08:03:22 -03:00
|
|
|
|
|
|
|
static AP_RangeFinder_Backend_Serial *create(
|
|
|
|
RangeFinder::RangeFinder_State &_state,
|
|
|
|
AP_RangeFinder_Params &_params) {
|
2024-05-26 22:24:14 -03:00
|
|
|
return NEW_NOTHROW AP_RangeFinder_BLPing(_state, _params);
|
2022-06-22 08:03:22 -03:00
|
|
|
}
|
2020-01-28 14:41:25 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Update class state
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
void update(void) override;
|
|
|
|
|
2023-07-27 23:46:53 -03:00
|
|
|
/**
|
|
|
|
* @brief Get the reading confidence
|
|
|
|
* 100 is best quality, 0 is worst
|
|
|
|
*
|
|
|
|
*/
|
2023-11-15 00:07:34 -04:00
|
|
|
int8_t get_signal_quality_pct() const override WARN_IF_UNUSED;
|
2023-07-27 23:46:53 -03:00
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
protected:
|
|
|
|
/**
|
|
|
|
* @brief Return the sensor type
|
|
|
|
*
|
|
|
|
* @return MAV_DISTANCE_SENSOR
|
|
|
|
*/
|
|
|
|
MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
|
|
|
|
return MAV_DISTANCE_SENSOR_ULTRASOUND;
|
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Sensor protocol class
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
PingProtocol protocol;
|
|
|
|
|
|
|
|
private:
|
2022-06-22 08:03:22 -03:00
|
|
|
|
|
|
|
using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
/**
|
|
|
|
* @brief Do the necessary sensor initiation
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
void init_sensor();
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Read serial interface and calculate new distance
|
|
|
|
*
|
2021-10-18 02:45:33 -03:00
|
|
|
* @param reading_m
|
2020-01-28 14:41:25 -04:00
|
|
|
* @return true
|
|
|
|
* @return false
|
|
|
|
*/
|
2021-10-18 02:45:33 -03:00
|
|
|
bool get_reading(float &reading_m) override;
|
2020-01-28 14:41:25 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Timeout between messages
|
|
|
|
*
|
|
|
|
* @return uint16_t
|
|
|
|
*/
|
|
|
|
uint16_t read_timeout_ms() const override { return 1000; }
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief system time that sensor was last initialised
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
uint32_t last_init_ms;
|
|
|
|
};
|
2022-03-12 06:37:29 -04:00
|
|
|
|
|
|
|
#endif
|