ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp

187 lines
6.0 KiB
C++
Raw Normal View History

2016-09-13 00:24:41 -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_LeddarOne.h"
#if AP_RANGEFINDER_LEDDARONE_ENABLED
2016-09-13 00:24:41 -03:00
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/crc.h>
2016-09-13 00:24:41 -03:00
extern const AP_HAL::HAL& hal;
// read - return last value measured by sensor
bool AP_RangeFinder_LeddarOne::get_reading(float &reading_m)
2016-09-13 00:24:41 -03:00
{
uint8_t number_detections;
LeddarOne_Status leddarone_status;
2016-09-13 00:24:41 -03:00
if (uart == nullptr) {
return false;
}
switch (modbus_status) {
case LEDDARONE_MODBUS_STATE_INIT: {
uart->discard_input();
2016-11-04 23:26:13 -03:00
// clear buffer and buffer_len
memset(read_buffer, 0, sizeof(read_buffer));
read_len = 0;
modbus_status = LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST;
}
// fall through to next state LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST
// immediately
FALLTHROUGH;
case LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST:
2016-11-04 23:26:13 -03:00
// send a request message for Modbus function 4
uart->write(send_request_buffer, sizeof(send_request_buffer));
modbus_status = LEDDARONE_MODBUS_STATE_SENT_REQUEST;
2016-11-04 23:26:13 -03:00
last_sending_request_ms = AP_HAL::millis();
FALLTHROUGH;
2016-11-04 23:26:13 -03:00
case LEDDARONE_MODBUS_STATE_SENT_REQUEST:
2016-11-04 23:26:13 -03:00
if (uart->available()) {
// change mod_bus status to read available buffer
modbus_status = LEDDARONE_MODBUS_STATE_AVAILABLE;
last_available_ms = AP_HAL::millis();
2016-11-04 23:26:13 -03:00
} else {
if (AP_HAL::millis() - last_sending_request_ms > 200) {
// reset mod_bus status to read new buffer
// if read_len is zero, send request without initialize
modbus_status = (read_len == 0) ? LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST : LEDDARONE_MODBUS_STATE_INIT;
}
2016-11-04 23:26:13 -03:00
}
break;
case LEDDARONE_MODBUS_STATE_AVAILABLE:
2016-11-04 23:26:13 -03:00
// parse a response message, set number_detections, detections and sum_distance
leddarone_status = parse_response(number_detections);
if (leddarone_status == LEDDARONE_STATE_OK) {
reading_m = (sum_distance_mm * 0.001f) / number_detections;
2016-11-04 23:26:13 -03:00
// reset mod_bus status to read new buffer
modbus_status = LEDDARONE_MODBUS_STATE_INIT;
2016-11-04 23:26:13 -03:00
return true;
}
// if status is not reading buffer, reset mod_bus status to read new buffer
else if (leddarone_status != LEDDARONE_STATE_READING_BUFFER || AP_HAL::millis() - last_available_ms > 200) {
2016-11-04 23:26:13 -03:00
// if read_len is zero, send request without initialize
modbus_status = (read_len == 0) ? LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST : LEDDARONE_MODBUS_STATE_INIT;
2016-11-04 23:26:13 -03:00
}
break;
}
return false;
2016-09-13 00:24:41 -03:00
}
/*
CRC16
CRC-16-IBM(x16+x15+x2+1)
*/
bool AP_RangeFinder_LeddarOne::CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck)
{
uint16_t crc = calc_crc_modbus(aBuffer, aLength);
2016-09-13 00:24:41 -03:00
uint8_t lCRCLo = LOWBYTE(crc);
uint8_t lCRCHi = HIGHBYTE(crc);
2016-09-13 00:24:41 -03:00
if (aCheck) {
return (aBuffer[aLength] == lCRCLo) && (aBuffer[aLength+1] == lCRCHi);
} else {
aBuffer[aLength] = lCRCLo;
aBuffer[aLength+1] = lCRCHi;
return true;
}
}
/*
parse a response message from Modbus
-----------------------------------------------
[ read buffer packet ]
-----------------------------------------------
0: slave address (LEDDARONE_DEFAULT_ADDRESS)
1: functions code
2: byte count
5-6-3-4: timestamp
7-8: internal temperature
9-10: number of detections
11-12: first distance
13-14: first amplitude
15-16: second distance
17-18: second amplitude
19-20: third distances
21-22: third amplitude
23: CRC Low
24: CRC High
-----------------------------------------------
2016-09-13 00:24:41 -03:00
*/
LeddarOne_Status AP_RangeFinder_LeddarOne::parse_response(uint8_t &number_detections)
2016-09-13 00:24:41 -03:00
{
uint8_t index_offset = LEDDARONE_DETECTION_DATA_INDEX_OFFSET;
2016-09-13 00:24:41 -03:00
// read serial
uint32_t nbytes = uart->available();
if (nbytes != 0) {
for (uint8_t index=read_len; index<nbytes+read_len; index++) {
if (index >= LEDDARONE_READ_BUFFER_SIZE) {
return LEDDARONE_STATE_ERR_BAD_RESPONSE;
2016-09-13 00:24:41 -03:00
}
read_buffer[index] = uart->read();
}
read_len += nbytes;
if (read_len < LEDDARONE_READ_BUFFER_SIZE) {
return LEDDARONE_STATE_READING_BUFFER;
2016-09-13 00:24:41 -03:00
}
}
2020-01-14 08:10:26 -04:00
// read_len is not 25 byte or function code is not 0x04
if (read_len != LEDDARONE_READ_BUFFER_SIZE || read_buffer[1] != LEDDARONE_MODOBUS_FUNCTION_CODE) {
return LEDDARONE_STATE_ERR_BAD_RESPONSE;
2016-09-13 00:24:41 -03:00
}
// CRC16
if (!CRC16(read_buffer, read_len-2, true)) {
return LEDDARONE_STATE_ERR_BAD_CRC;
2016-09-13 00:24:41 -03:00
}
// number of detections (index:10)
number_detections = read_buffer[LEDDARONE_DETECTION_DATA_NUMBER_INDEX];
2016-09-13 00:24:41 -03:00
// if the number of detection is over or zero , it is false
if (number_detections > LEDDARONE_DETECTIONS_MAX || number_detections == 0) {
return LEDDARONE_STATE_ERR_NUMBER_DETECTIONS;
2016-09-13 00:24:41 -03:00
}
sum_distance_mm = 0;
for (uint8_t index=0; index<number_detections; index++) {
// construct data word from two bytes
sum_distance_mm += read_buffer[index_offset]<<8 | read_buffer[index_offset+1];
// add index offset (4) to read next detection data
index_offset += LEDDARONE_DETECTION_DATA_OFFSET;
2016-09-13 00:24:41 -03:00
}
return LEDDARONE_STATE_OK;
2016-09-13 00:24:41 -03:00
}
#endif // AP_RANGEFINDER_LEDDARONE_ENABLED