|
|
|
/*
|
|
|
|
* Copyright (C) 2016 Intel Corporation. All rights reserved.
|
|
|
|
*
|
|
|
|
* This file 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 file 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_SerialManager/AP_SerialManager.h>
|
|
|
|
#include <ctype.h>
|
|
|
|
#include "AP_RangeFinder_MaxsonarSerialLV.h"
|
|
|
|
|
|
|
|
#define MAXSONAR_SERIAL_LV_BAUD_RATE 9600
|
|
|
|
|
|
|
|
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_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
|
|
|
|
AP_RangeFinder_Params &_params,
|
|
|
|
uint8_t serial_instance) :
|
|
|
|
AP_RangeFinder_Backend(_state, _params)
|
|
|
|
{
|
|
|
|
const AP_SerialManager &serial_manager = AP::serialmanager();
|
|
|
|
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
|
|
|
if (uart != nullptr) {
|
|
|
|
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
detect if a MaxSonar 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_MaxsonarSerialLV::detect(uint8_t serial_instance)
|
|
|
|
{
|
|
|
|
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
|
|
|
}
|
|
|
|
|
|
|
|
// read - return last value measured by sensor
|
|
|
|
bool AP_RangeFinder_MaxsonarSerialLV::get_reading(uint16_t &reading_cm)
|
|
|
|
{
|
|
|
|
if (uart == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
#if 1
|
|
|
|
float sum = 0;
|
|
|
|
int16_t nbytes = uart->available();
|
|
|
|
uint16_t count = 0;
|
|
|
|
|
|
|
|
while (nbytes-- > 0) {
|
|
|
|
char c = uart->read();
|
|
|
|
// gcs().send_text(MAV_SEVERITY_INFO, "getc #%c",c);
|
|
|
|
// gcs().send_text(MAV_SEVERITY_INFO, "getd #%d",(int)atoi(c);
|
|
|
|
// gcs().send_text(MAV_SEVERITY_INFO, "getf #%f",(float)atof(c));
|
|
|
|
|
|
|
|
if (c == '\r') {
|
|
|
|
linebuf[linebuf_len] = 0;
|
|
|
|
// sum += (int)atoi(linebuf);
|
|
|
|
sum += (float)atof(linebuf);
|
|
|
|
count++;
|
|
|
|
linebuf_len = 0;
|
|
|
|
// gcs().send_text(MAV_SEVERITY_INFO, "dist #%3.2f",sum);
|
|
|
|
// } else if (isdigit() {
|
|
|
|
} else {
|
|
|
|
linebuf[linebuf_len++] = c;
|
|
|
|
if (linebuf_len == sizeof(linebuf)) {
|
|
|
|
// too long, discard the line
|
|
|
|
linebuf_len = 0;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (count == 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// This sonar gives the metrics in inches, so we have to transform this to centimeters
|
|
|
|
// reading_cm = 2.54f * sum / count;
|
|
|
|
reading_cm = 100.0f * sum / count;
|
|
|
|
|
|
|
|
return true;
|
|
|
|
#else
|
|
|
|
|
|
|
|
uint8_t frameOK = 0;
|
|
|
|
uint16_t Range = 0; //雷达实测距离
|
|
|
|
int16_t nbytes = uart->available();
|
|
|
|
|
|
|
|
while ( nbytes-- > 0 ) {
|
|
|
|
if( uart->read() == StartSequence ){ //判断数据包帧头0xAA
|
|
|
|
string[0] = StartSequence;
|
|
|
|
if( uart->read() == StartSequence ){ //判断数据包帧头0xAA
|
|
|
|
string[1] = StartSequence;
|
|
|
|
for( int i = 2;i < 14;i++ ){ //存储数据到数组
|
|
|
|
string[i] = uart->read();
|
|
|
|
}
|
|
|
|
CheckSum = string[4]+string[5]+string[6]+string[7]+string[8]+string[9]+string[10];
|
|
|
|
if( string[11] == (CheckSum&0xFF)&&string[12] == EndSequence && string[13] == EndSequence ){ //按照协议对收到的数据进行校验
|
|
|
|
frameOK = 1;
|
|
|
|
Range = (string[6]*256+string[7]); //cm
|
|
|
|
// testdata = (string[8]*256+string[9]);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (frameOK == 0)
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if(Range != 0)
|
|
|
|
{
|
|
|
|
reading_cm = Range;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
update the state of the sensor
|
|
|
|
*/
|
|
|
|
void AP_RangeFinder_MaxsonarSerialLV::update(void)
|
|
|
|
{
|
|
|
|
if (get_reading(state.distance_cm)) {
|
|
|
|
// update range_valid state based on distance measured
|
AP_RangeFinder: support last_reading_ms
Benewake, LeddarOne, LightWareSerial, MAVLink, MaxsonarI2CXL, MaxsonarSerialLV, NMEA, PX4_PWM, uLanding and Wasp already stored the last read time so for these drivers, this change just moves that storage to the state structure
analog, BBB_PRU, Bebop, LightWareI2C, PulsedLightLRF, TeraRangerI2C, VL53L0X did not store the last read time so this was added
7 years ago
|
|
|
state.last_reading_ms = AP_HAL::millis();
|
|
|
|
update_status();
|
AP_RangeFinder: support last_reading_ms
Benewake, LeddarOne, LightWareSerial, MAVLink, MaxsonarI2CXL, MaxsonarSerialLV, NMEA, PX4_PWM, uLanding and Wasp already stored the last read time so for these drivers, this change just moves that storage to the state structure
analog, BBB_PRU, Bebop, LightWareI2C, PulsedLightLRF, TeraRangerI2C, VL53L0X did not store the last read time so this was added
7 years ago
|
|
|
} else if (AP_HAL::millis() - state.last_reading_ms > 500) {
|
|
|
|
set_status(RangeFinder::RangeFinder_NoData);
|
|
|
|
}
|
|
|
|
}
|