AP_RangeFinder: add LeddarOne support

This commit is contained in:
ShingoMatsuura 2016-09-13 12:24:41 +09:00 committed by Randy Mackay
parent 084862a999
commit 3123bd6d7d
4 changed files with 286 additions and 1 deletions

View File

@ -0,0 +1,224 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
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_HAL/AP_HAL.h>
#include "AP_RangeFinder_LeddarOne.h"
#include <AP_SerialManager/AP_SerialManager.h>
#include <ctype.h>
extern const AP_HAL::HAL& hal;
/*
The constructor also initialises the rangefinder. Note that this
constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder
*/
AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder &_ranger, uint8_t instance,
RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager) :
AP_RangeFinder_Backend(_ranger, instance, _state)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, 0);
if (uart != nullptr) {
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar, 0));
}
}
/*
detect if a LeddarOne rangefinder is connected. We'll detect by
trying to take a reading on Serial. If we get a result the sensor is
there.
*/
bool AP_RangeFinder_LeddarOne::detect(RangeFinder &_ranger, uint8_t instance, AP_SerialManager &serial_manager)
{
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, 0) != nullptr;
}
// read - return last value measured by sensor
bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm)
{
if (uart == nullptr) {
return false;
}
// send a request message for Modbus function 4
if (send_request() < 0) {
return false;
}
uint32_t start_ms = AP_HAL::millis();
while (!uart->available()) {
// wait up to 200ms
if (AP_HAL::millis() - start_ms > 200) {
return false;
}
}
// parse a response message, set detections and sum_distance
if (parse_response() <= 0) {
return false;
}
// calculate average distance
reading_cm = sum_distance / number_detections;
return true;
}
/*
update the state of the sensor
*/
void AP_RangeFinder_LeddarOne::update(void)
{
if (get_reading(state.distance_cm)) {
// update range_valid state based on distance measured
last_reading_ms = AP_HAL::millis();
update_status();
} else if (AP_HAL::millis() - last_reading_ms > 200) {
set_status(RangeFinder::RangeFinder_NoData);
}
}
/*
CRC16
CRC-16-IBM(x16+x15+x2+1)
*/
bool AP_RangeFinder_LeddarOne::CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck)
{
uint16_t crc = 0xFFFF;
uint32_t i = 0;
uint32_t j = 0;
uint8_t lCRCHi = 0;
uint8_t lCRCLo = 0;
for (i=0; i<aLength; i++) {
crc ^= aBuffer[i];
for (j=0; j<8; j++) {
if (crc & 1) {
crc = (crc >> 1) ^ 0xA001;
} else {
crc >>= 1;
}
}
}
lCRCLo = LOWBYTE(crc);
lCRCHi = HIGHBYTE(crc);
if (aCheck) {
return (aBuffer[aLength] == lCRCLo) && (aBuffer[aLength+1] == lCRCHi);
} else {
aBuffer[aLength] = lCRCLo;
aBuffer[aLength+1] = lCRCHi;
return true;
}
}
/*
send a request message to execute ModBus function 0x04
*/
int8_t AP_RangeFinder_LeddarOne::send_request(void)
{
uint8_t data_buffer[10] = {0};
uint8_t i = 0;
int32_t nbytes = uart->available();
// clear buffer
while (nbytes-- > 0) {
uart->read();
if (++i > 250) {
return LEDDARONE_ERR_SERIAL_PORT;
}
}
// Modbus read input register (function code 0x04)
data_buffer[0] = LEDDARONE_DEFAULT_ADDRESS;
data_buffer[1] = 0x04;
data_buffer[2] = 0;
data_buffer[3] = 20;
data_buffer[4] = 0;
data_buffer[5] = 10;
// CRC16
CRC16(data_buffer, 6, false);
// write buffer data with CRC16 bits
for (i=0; i<8; i++) {
uart->write(data_buffer[i]);
}
uart->flush();
return 0;
}
/*
parse a response message from Modbus
*/
int8_t AP_RangeFinder_LeddarOne::parse_response(void)
{
uint8_t data_buffer[25] = {0};
uint32_t start_ms = AP_HAL::millis();
uint32_t nbytes = 0;
uint32_t len =0;
uint8_t i = 0;
uint8_t index_offset = 11;
// read serial
while (AP_HAL::millis() - start_ms < 10) {
nbytes = uart->available();
if (len == 25 && nbytes == 0) {
break;
} else {
for (i=len; i<nbytes+len; i++) {
if (i >= 25) {
return LEDDARONE_ERR_BAD_RESPONSE;
}
data_buffer[i] = uart->read();
}
start_ms = AP_HAL::millis();
len += nbytes;
}
}
if (len != 25) {
return LEDDARONE_ERR_BAD_RESPONSE;
}
// CRC16
if (!CRC16(data_buffer, len-2, true)) {
return LEDDARONE_ERR_BAD_CRC;
}
// number of detections
number_detections = data_buffer[10];
// if the number of detection is over , it is false
if (number_detections > (sizeof(detections) / sizeof(detections[0]))) {
return LEDDARONE_ERR_NUMBER_DETECTIONS;
}
memset(detections, 0, sizeof(detections));
sum_distance = 0;
for (i=0; i<number_detections; i++) {
// mm to cm
detections[i] = (((uint16_t)data_buffer[index_offset])*256 + data_buffer[index_offset+1]) / 10;
sum_distance += detections[i];
index_offset += 4;
}
return number_detections;
}

View File

@ -0,0 +1,52 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#pragma once
#include "RangeFinder.h"
#include "RangeFinder_Backend.h"
#include <GCS_MAVLink/GCS.h>
// default slave address
#define LEDDARONE_DEFAULT_ADDRESS 0x01
// error codes
#define LEDDARONE_ERR_BAD_CRC -1
#define LEDDARONE_ERR_NO_RESPONSES -2
#define LEDDARONE_ERR_BAD_RESPONSE -3
#define LEDDARONE_ERR_SHORT_RESPONSE -4
#define LEDDARONE_ERR_SERIAL_PORT -5
#define LEDDARONE_ERR_NUMBER_DETECTIONS -6
class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend
{
public:
// constructor
AP_RangeFinder_LeddarOne(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state,
AP_SerialManager &serial_manager);
// static detection function
static bool detect(RangeFinder &ranger, uint8_t instance, AP_SerialManager &serial_manager);
// update state
void update(void);
private:
// get a reading
bool get_reading(uint16_t &reading_cm);
// CRC16
bool CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck);
// send a request message to execute ModBus function
int8_t send_request(void);
// parse a response message from ModBus
int8_t parse_response(void);
AP_HAL::UARTDriver *uart = nullptr;
uint32_t last_reading_ms = 0;
uint16_t detections[3];
uint8_t number_detections = 0;
uint32_t sum_distance = 0;
};

View File

@ -25,6 +25,7 @@
#include "AP_RangeFinder_LightWareSerial.h"
#include "AP_RangeFinder_Bebop.h"
#include "AP_RangeFinder_MAVLink.h"
#include "AP_RangeFinder_LeddarOne.h"
extern const AP_HAL::HAL &hal;
@ -537,6 +538,13 @@ void RangeFinder::detect_instance(uint8_t instance)
return;
}
}
if (type == RangeFinder_TYPE_LEDDARONE) {
if (AP_RangeFinder_LeddarOne::detect(*this, instance, serial_manager)) {
state[instance].instance = instance;
drivers[instance] = new AP_RangeFinder_LeddarOne(*this, instance, state[instance], serial_manager);
return;
}
}
#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
if (type == RangeFinder_TYPE_BEBOP) {

View File

@ -48,7 +48,8 @@ public:
RangeFinder_TYPE_LWI2C = 7,
RangeFinder_TYPE_LWSER = 8,
RangeFinder_TYPE_BEBOP = 9,
RangeFinder_TYPE_MAVLink = 10
RangeFinder_TYPE_MAVLink = 10,
RangeFinder_TYPE_LEDDARONE = 12
};
enum RangeFinder_Function {