2019-03-28 09:43:23 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "AP_RangeFinder_BLPing.h"
|
|
|
|
|
2022-03-12 06:37:29 -04:00
|
|
|
#if AP_RANGEFINDER_BLPING_ENABLED
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
2019-03-28 09:43:23 -03:00
|
|
|
void AP_RangeFinder_BLPing::update(void)
|
|
|
|
{
|
|
|
|
if (uart == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
2019-11-01 08:00:04 -03:00
|
|
|
AP_RangeFinder_Backend_Serial::update();
|
2019-03-28 09:43:23 -03:00
|
|
|
|
2019-11-01 08:00:04 -03:00
|
|
|
if (status() == RangeFinder::Status::NoData) {
|
|
|
|
const uint32_t now = AP_HAL::millis();
|
2019-03-28 09:43:23 -03:00
|
|
|
// initialise sensor if no distances recently
|
2020-01-28 14:41:25 -04:00
|
|
|
if (now - last_init_ms > read_timeout_ms()) {
|
2019-03-28 09:43:23 -03:00
|
|
|
last_init_ms = now;
|
|
|
|
init_sensor();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_RangeFinder_BLPing::init_sensor()
|
|
|
|
{
|
2020-01-28 14:41:25 -04:00
|
|
|
// Set message interval between pings in ms
|
|
|
|
uint16_t ping_interval = _sensor_rate_ms;
|
|
|
|
protocol.send_message(uart, PingProtocol::MessageId::SET_PING_INTERVAL, reinterpret_cast<uint8_t*>(&ping_interval), sizeof(ping_interval));
|
|
|
|
|
|
|
|
// Send a message requesting a continuous
|
|
|
|
uint16_t continuous_message = static_cast<uint16_t>(PingProtocol::MessageId::DISTANCE_SIMPLE);
|
|
|
|
protocol.send_message(uart, PingProtocol::MessageId::CONTINUOUS_START, reinterpret_cast<uint8_t*>(&continuous_message), sizeof(continuous_message));
|
2019-03-28 09:43:23 -03:00
|
|
|
}
|
|
|
|
|
2021-10-18 02:45:33 -03:00
|
|
|
// distance returned in reading_m, signal_ok is set to true if sensor reports a strong signal
|
|
|
|
bool AP_RangeFinder_BLPing::get_reading(float &reading_m)
|
2020-01-28 14:41:25 -04:00
|
|
|
{
|
|
|
|
if (uart == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct {
|
|
|
|
float sum_cm = 0;
|
|
|
|
uint16_t count = 0;
|
2021-02-01 12:26:33 -04:00
|
|
|
float mean() const { return sum_cm / count; };
|
2020-01-28 14:41:25 -04:00
|
|
|
} averageStruct;
|
|
|
|
|
|
|
|
// read any available lines from the lidar
|
|
|
|
int16_t nbytes = uart->available();
|
|
|
|
while (nbytes-- > 0) {
|
|
|
|
const int16_t b = uart->read();
|
|
|
|
if (b < 0) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
if (protocol.parse_byte(b) == PingProtocol::MessageId::DISTANCE_SIMPLE) {
|
|
|
|
averageStruct.count++;
|
|
|
|
averageStruct.sum_cm += protocol.get_distance_mm()/10.0f;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (averageStruct.count > 0) {
|
|
|
|
// return average distance of readings
|
2021-10-18 02:45:33 -03:00
|
|
|
reading_m = averageStruct.mean() * 0.01f;
|
2020-01-28 14:41:25 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// no readings so return false
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2023-07-27 23:46:53 -03:00
|
|
|
bool AP_RangeFinder_BLPing::get_signal_quality_pct(int8_t &quality_pct) const
|
|
|
|
{
|
|
|
|
if (status() != RangeFinder::Status::Good) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
quality_pct = protocol.get_confidence();
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
uint8_t PingProtocol::get_confidence() const
|
|
|
|
{
|
|
|
|
return msg.payload[4];
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t PingProtocol::get_distance_mm() const
|
|
|
|
{
|
|
|
|
return (uint32_t)msg.payload[0] |
|
|
|
|
(uint32_t)msg.payload[1] << 8 |
|
|
|
|
(uint32_t)msg.payload[2] << 16 |
|
|
|
|
(uint32_t)msg.payload[3] << 24;
|
|
|
|
}
|
|
|
|
|
|
|
|
void PingProtocol::send_message(AP_HAL::UARTDriver *uart, PingProtocol::MessageId msg_id, const uint8_t *payload, uint16_t payload_len) const
|
2019-03-28 09:43:23 -03:00
|
|
|
{
|
|
|
|
if (uart == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for sufficient space in outgoing buffer
|
|
|
|
if (uart->txspace() < payload_len + 10U) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// write header
|
2020-01-28 14:41:25 -04:00
|
|
|
uart->write(_frame_header1);
|
|
|
|
uart->write(_frame_header2);
|
|
|
|
uint16_t crc = _frame_header1 + _frame_header2;
|
2019-03-28 09:43:23 -03:00
|
|
|
|
|
|
|
// write payload length
|
|
|
|
uart->write(LOWBYTE(payload_len));
|
|
|
|
uart->write(HIGHBYTE(payload_len));
|
|
|
|
crc += LOWBYTE(payload_len) + HIGHBYTE(payload_len);
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
// message id
|
|
|
|
uart->write(LOWBYTE(msg_id));
|
|
|
|
uart->write(HIGHBYTE(msg_id));
|
|
|
|
crc += LOWBYTE(msg_id) + HIGHBYTE(msg_id);
|
2019-03-28 09:43:23 -03:00
|
|
|
|
|
|
|
// src dev id
|
2020-01-28 14:41:25 -04:00
|
|
|
uart->write(_src_id);
|
|
|
|
crc += _src_id;
|
2019-03-28 09:43:23 -03:00
|
|
|
|
|
|
|
// destination dev id
|
2020-01-28 14:41:25 -04:00
|
|
|
uart->write(_dst_id);
|
|
|
|
crc += _dst_id;
|
2019-03-28 09:43:23 -03:00
|
|
|
|
|
|
|
// payload
|
|
|
|
if (payload != nullptr) {
|
|
|
|
for (uint16_t i = 0; i<payload_len; i++) {
|
|
|
|
uart->write(payload[i]);
|
|
|
|
crc += payload[i];
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// checksum
|
|
|
|
uart->write(LOWBYTE(crc));
|
|
|
|
uart->write(HIGHBYTE(crc));
|
|
|
|
}
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
PingProtocol::MessageId PingProtocol::parse_byte(uint8_t b)
|
2019-03-28 09:43:23 -03:00
|
|
|
{
|
|
|
|
// process byte depending upon current state
|
|
|
|
switch (msg.state) {
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::HEADER1:
|
|
|
|
if (b == _frame_header1) {
|
|
|
|
msg.crc_expected = _frame_header1;
|
|
|
|
msg.state = ParserState::HEADER2;
|
|
|
|
msg.done = false;
|
2019-03-28 09:43:23 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::HEADER2:
|
|
|
|
if (b == _frame_header2) {
|
|
|
|
msg.crc_expected += _frame_header2;
|
|
|
|
msg.state = ParserState::LEN_L;
|
2019-03-28 09:43:23 -03:00
|
|
|
} else {
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::HEADER1;
|
2019-03-28 09:43:23 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::LEN_L:
|
2019-03-28 09:43:23 -03:00
|
|
|
msg.payload_len = b;
|
|
|
|
msg.crc_expected += b;
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::LEN_H;
|
2019-03-28 09:43:23 -03:00
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::LEN_H:
|
2019-03-28 09:43:23 -03:00
|
|
|
msg.payload_len |= ((uint16_t)b << 8);
|
|
|
|
msg.payload_recv = 0;
|
|
|
|
msg.crc_expected += b;
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::MSG_ID_L;
|
2019-03-28 09:43:23 -03:00
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::MSG_ID_L:
|
|
|
|
msg.id = b;
|
2019-03-28 09:43:23 -03:00
|
|
|
msg.crc_expected += b;
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::MSG_ID_H;
|
2019-03-28 09:43:23 -03:00
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::MSG_ID_H:
|
|
|
|
msg.id |= ((uint16_t)b << 8);
|
2019-03-28 09:43:23 -03:00
|
|
|
msg.crc_expected += b;
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::SRC_ID;
|
2019-03-28 09:43:23 -03:00
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::SRC_ID:
|
2019-03-28 09:43:23 -03:00
|
|
|
msg.crc_expected += b;
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::DST_ID;
|
2019-03-28 09:43:23 -03:00
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::DST_ID:
|
2019-03-28 09:43:23 -03:00
|
|
|
msg.crc_expected += b;
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::PAYLOAD;
|
2019-03-28 09:43:23 -03:00
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::PAYLOAD:
|
2019-03-28 09:43:23 -03:00
|
|
|
if (msg.payload_recv < msg.payload_len) {
|
|
|
|
if (msg.payload_recv < ARRAY_SIZE(msg.payload)) {
|
|
|
|
msg.payload[msg.payload_recv] = b;
|
|
|
|
}
|
|
|
|
msg.payload_recv++;
|
|
|
|
msg.crc_expected += b;
|
|
|
|
}
|
|
|
|
if (msg.payload_recv == msg.payload_len) {
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::CRC_L;
|
2019-03-28 09:43:23 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::CRC_L:
|
2019-03-28 09:43:23 -03:00
|
|
|
msg.crc = b;
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::CRC_H;
|
2019-03-28 09:43:23 -03:00
|
|
|
break;
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
case ParserState::CRC_H:
|
2019-03-28 09:43:23 -03:00
|
|
|
msg.crc |= ((uint16_t)b << 8);
|
2020-01-28 14:41:25 -04:00
|
|
|
msg.state = ParserState::HEADER1;
|
|
|
|
msg.done = msg.crc_expected == msg.crc;
|
2019-03-28 09:43:23 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2020-01-28 14:41:25 -04:00
|
|
|
|
|
|
|
return msg.done ? get_message_id() : MessageId::INVALID;
|
2019-03-28 09:43:23 -03:00
|
|
|
}
|
2022-03-12 06:37:29 -04:00
|
|
|
|
|
|
|
#endif // AP_RANGEFINDER_BLPING_ENABLED
|