2017-07-07 13:04:55 -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/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
|
|
|
* ArduPilot device driver for SLAMTEC RPLIDAR A2 (16m range version)
|
|
|
|
*
|
|
|
|
* ALL INFORMATION REGARDING PROTOCOL WAS DERIVED FROM RPLIDAR DATASHEET:
|
|
|
|
*
|
|
|
|
* https://www.slamtec.com/en/Lidar
|
|
|
|
* http://bucket.download.slamtec.com/63ac3f0d8c859d3a10e51c6b3285fcce25a47357/LR001_SLAMTEC_rplidar_protocol_v1.0_en.pdf
|
|
|
|
*
|
|
|
|
* Author: Steven Josefs, IAV GmbH
|
|
|
|
* Based on the LightWare SF40C ArduPilot device driver from Randy Mackay
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
2023-05-11 23:19:00 -03:00
|
|
|
/*
|
|
|
|
|
|
|
|
# to connect device to SITL:
|
|
|
|
./Tools/autotest/sim_vehicle.py -v Rover --gdb --debug -A --serial5=uart:/dev/serial/by-id/usb-Silicon_Labs_CP2102_USB_to_UART_Bridge_Controller_0001-if00-port0:115200
|
|
|
|
param set SERIAL5_PROTOCOL 11
|
|
|
|
param set SERIAL5_BAUD 115200
|
|
|
|
param set PRX1_TYPE 5
|
|
|
|
reboot
|
|
|
|
|
|
|
|
# short outer-two wires on JST plug to get it to spin
|
|
|
|
|
|
|
|
*/
|
|
|
|
|
2017-07-07 13:04:55 -03:00
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
2023-04-05 09:25:54 -03:00
|
|
|
#include "AP_Proximity_config.h"
|
|
|
|
|
|
|
|
#if AP_PROXIMITY_RPLIDARA2_ENABLED
|
2017-07-07 13:04:55 -03:00
|
|
|
|
2023-04-05 09:25:54 -03:00
|
|
|
#include "AP_Proximity_Backend_Serial.h"
|
2017-07-07 13:04:55 -03:00
|
|
|
|
2019-12-04 00:53:05 -04:00
|
|
|
class AP_Proximity_RPLidarA2 : public AP_Proximity_Backend_Serial
|
2017-07-07 13:04:55 -03:00
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
2019-12-04 00:53:05 -04:00
|
|
|
using AP_Proximity_Backend_Serial::AP_Proximity_Backend_Serial;
|
2017-07-07 13:04:55 -03:00
|
|
|
|
|
|
|
// update state
|
2018-11-07 07:01:30 -04:00
|
|
|
void update(void) override;
|
2017-07-07 13:04:55 -03:00
|
|
|
|
|
|
|
// get maximum and minimum distances (in meters) of sensor
|
2018-11-07 07:01:30 -04:00
|
|
|
float distance_max() const override;
|
|
|
|
float distance_min() const override;
|
2017-07-07 13:04:55 -03:00
|
|
|
|
|
|
|
private:
|
|
|
|
|
2020-05-21 20:37:40 -03:00
|
|
|
enum class State {
|
|
|
|
RESET = 56,
|
|
|
|
AWAITING_RESPONSE,
|
|
|
|
AWAITING_SCAN_DATA,
|
|
|
|
AWAITING_HEALTH,
|
2021-02-04 21:12:24 -04:00
|
|
|
AWAITING_DEVICE_INFO,
|
2020-05-21 20:37:40 -03:00
|
|
|
} _state = State::RESET;
|
2017-07-07 13:04:55 -03:00
|
|
|
|
|
|
|
// send request for something from sensor
|
|
|
|
void send_request_for_health();
|
2020-05-21 20:37:40 -03:00
|
|
|
void send_scan_mode_request();
|
2021-02-04 21:12:24 -04:00
|
|
|
void send_request_for_device_info();
|
2020-05-21 20:37:40 -03:00
|
|
|
|
2017-07-07 13:04:55 -03:00
|
|
|
void parse_response_data();
|
2020-05-21 20:37:40 -03:00
|
|
|
void parse_response_health();
|
2021-02-04 21:12:24 -04:00
|
|
|
void parse_response_device_info();
|
2020-05-21 20:37:40 -03:00
|
|
|
|
2017-07-07 13:04:55 -03:00
|
|
|
void get_readings();
|
|
|
|
void reset_rplidar();
|
2020-05-21 20:37:40 -03:00
|
|
|
void reset();
|
2017-07-07 13:04:55 -03:00
|
|
|
|
2020-05-21 20:37:40 -03:00
|
|
|
// remove bytes from read buffer:
|
|
|
|
void consume_bytes(uint16_t count);
|
2017-07-07 13:04:55 -03:00
|
|
|
|
2023-05-12 02:53:19 -03:00
|
|
|
uint8_t _sync_error;
|
2017-07-07 13:04:55 -03:00
|
|
|
uint16_t _byte_count;
|
|
|
|
|
|
|
|
// request related variables
|
|
|
|
uint32_t _last_distance_received_ms; ///< system time of last distance measurement received from sensor
|
|
|
|
uint32_t _last_reset_ms;
|
|
|
|
|
2020-12-14 03:59:41 -04:00
|
|
|
// face related variables
|
|
|
|
AP_Proximity_Boundary_3D::Face _last_face;///< last face requested
|
|
|
|
float _last_angle_deg; ///< yaw angle (in degrees) of _last_distance_m
|
|
|
|
float _last_distance_m; ///< shortest distance for _last_face
|
|
|
|
bool _last_distance_valid; ///< true if _last_distance_m is valid
|
2017-07-07 13:04:55 -03:00
|
|
|
|
2021-02-04 21:12:24 -04:00
|
|
|
struct PACKED _device_info {
|
|
|
|
uint8_t model;
|
|
|
|
uint8_t firmware_minor;
|
|
|
|
uint8_t firmware_major;
|
|
|
|
uint8_t hardware;
|
|
|
|
uint8_t serial[16];
|
|
|
|
};
|
|
|
|
|
2017-07-07 13:04:55 -03:00
|
|
|
struct PACKED _sensor_scan {
|
|
|
|
uint8_t startbit : 1; ///< on the first revolution 1 else 0
|
|
|
|
uint8_t not_startbit : 1; ///< complementary to startbit
|
|
|
|
uint8_t quality : 6; ///< Related the reflected laser pulse strength
|
|
|
|
uint8_t checkbit : 1; ///< always set to 1
|
|
|
|
uint16_t angle_q6 : 15; ///< Actual heading = angle_q6/64.0 Degree
|
|
|
|
uint16_t distance_q2 : 16; ///< Actual Distance = distance_q2/4.0 mm
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED _sensor_health {
|
|
|
|
uint8_t status; ///< status definition: 0 good, 1 warning, 2 error
|
|
|
|
uint16_t error_code; ///< the related error code
|
|
|
|
};
|
|
|
|
|
2020-05-21 20:37:40 -03:00
|
|
|
struct PACKED _descriptor {
|
|
|
|
uint8_t bytes[7];
|
|
|
|
};
|
|
|
|
|
|
|
|
// we don't actually *need* to store this. If we don't, _payload
|
|
|
|
// can be just 7 bytes, but that doesn't make for efficient
|
|
|
|
// reading. It also simplifies the state machine to have the read
|
|
|
|
// buffer at least this big. Note that we force the buffer to a
|
|
|
|
// larger size below anyway.
|
|
|
|
struct PACKED _rpi_information {
|
|
|
|
uint8_t bytes[63];
|
|
|
|
};
|
|
|
|
|
2017-07-07 13:04:55 -03:00
|
|
|
union PACKED {
|
|
|
|
DEFINE_BYTE_ARRAY_METHODS
|
|
|
|
_sensor_scan sensor_scan;
|
|
|
|
_sensor_health sensor_health;
|
2020-05-21 20:37:40 -03:00
|
|
|
_descriptor descriptor;
|
|
|
|
_rpi_information information;
|
2021-02-04 21:12:24 -04:00
|
|
|
_device_info device_info;
|
2023-05-11 23:52:04 -03:00
|
|
|
uint8_t forced_buffer_size[256]; // just so we read(...) efficiently
|
2020-05-21 20:37:40 -03:00
|
|
|
} _payload;
|
|
|
|
static_assert(sizeof(_payload) >= 63, "Needed for parsing out reboot data");
|
|
|
|
|
2021-02-04 21:12:24 -04:00
|
|
|
enum class Model {
|
|
|
|
UNKNOWN,
|
2021-02-04 21:30:38 -04:00
|
|
|
A1,
|
2021-02-04 21:12:24 -04:00
|
|
|
A2,
|
2023-05-12 01:25:49 -03:00
|
|
|
S1,
|
2021-02-04 21:12:24 -04:00
|
|
|
} model = Model::UNKNOWN;
|
2020-05-21 20:37:40 -03:00
|
|
|
|
|
|
|
bool make_first_byte_in_payload(uint8_t desired_byte);
|
2017-07-07 13:04:55 -03:00
|
|
|
};
|
2021-03-25 04:32:09 -03:00
|
|
|
|
2023-04-05 09:25:54 -03:00
|
|
|
#endif // AP_PROXIMITY_RPLIDARA2_ENABLED
|