2016-08-15 03:17:15 -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/>.
|
|
|
|
*/
|
|
|
|
|
2019-11-13 07:10:53 -04:00
|
|
|
#include "AP_Proximity_LightWareSF40C_v09.h"
|
2021-03-25 04:32:09 -03:00
|
|
|
|
|
|
|
#if HAL_PROXIMITY_ENABLED
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-08-15 03:17:15 -03:00
|
|
|
#include <ctype.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
// update the state of the sensor
|
2019-11-13 07:10:53 -04:00
|
|
|
void AP_Proximity_LightWareSF40C_v09::update(void)
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
2019-12-04 00:59:07 -04:00
|
|
|
if (_uart == nullptr) {
|
2016-08-15 03:17:15 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// initialise sensor if necessary
|
|
|
|
bool initialised = initialise();
|
|
|
|
|
|
|
|
// process incoming messages
|
|
|
|
check_for_reply();
|
|
|
|
|
|
|
|
// request new data from sensor
|
|
|
|
if (initialised) {
|
|
|
|
request_new_data();
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for timeout and set health status
|
|
|
|
if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_SF40C_TIMEOUT_MS)) {
|
2019-09-27 05:58:52 -03:00
|
|
|
set_status(AP_Proximity::Status::NoData);
|
2016-08-15 03:17:15 -03:00
|
|
|
} else {
|
2019-09-27 05:58:52 -03:00
|
|
|
set_status(AP_Proximity::Status::Good);
|
2016-08-15 03:17:15 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-11-25 01:01:21 -04:00
|
|
|
// get maximum and minimum distances (in meters) of primary sensor
|
2019-11-13 07:10:53 -04:00
|
|
|
float AP_Proximity_LightWareSF40C_v09::distance_max() const
|
2016-11-25 01:01:21 -04:00
|
|
|
{
|
|
|
|
return 100.0f;
|
|
|
|
}
|
2019-11-13 07:10:53 -04:00
|
|
|
float AP_Proximity_LightWareSF40C_v09::distance_min() const
|
2016-11-25 01:01:21 -04:00
|
|
|
{
|
|
|
|
return 0.20f;
|
|
|
|
}
|
|
|
|
|
2020-06-02 21:24:15 -03:00
|
|
|
// initialise sensor (returns true if sensor is successfully initialised)
|
2019-11-13 07:10:53 -04:00
|
|
|
bool AP_Proximity_LightWareSF40C_v09::initialise()
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
|
|
|
// set motor direction once per second
|
|
|
|
if (_motor_direction > 1) {
|
|
|
|
if ((_last_request_ms == 0) || AP_HAL::millis() - _last_request_ms > 1000) {
|
|
|
|
set_motor_direction();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
// set forward direction once per second
|
|
|
|
if (_forward_direction != frontend.get_yaw_correction(state.instance)) {
|
|
|
|
if ((_last_request_ms == 0) || AP_HAL::millis() - _last_request_ms > 1000) {
|
|
|
|
set_forward_direction();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
// request motors turn on once per second
|
|
|
|
if (_motor_speed == 0) {
|
|
|
|
if ((_last_request_ms == 0) || AP_HAL::millis() - _last_request_ms > 1000) {
|
|
|
|
set_motor_speed(true);
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2016-11-15 03:27:34 -04:00
|
|
|
|
2019-12-03 22:46:03 -04:00
|
|
|
return true;
|
2016-11-15 03:27:34 -04:00
|
|
|
}
|
|
|
|
|
2016-08-15 03:17:15 -03:00
|
|
|
// set speed of rotating motor
|
2019-11-13 07:10:53 -04:00
|
|
|
void AP_Proximity_LightWareSF40C_v09::set_motor_speed(bool on_off)
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
|
|
|
// exit immediately if no uart
|
2019-12-04 00:59:07 -04:00
|
|
|
if (_uart == nullptr) {
|
2016-08-15 03:17:15 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set motor update speed
|
|
|
|
if (on_off) {
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write("#MBS,3\r\n"); // send request to spin motor at 4.5hz
|
2016-08-15 03:17:15 -03:00
|
|
|
} else {
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write("#MBS,0\r\n"); // send request to stop motor
|
2016-08-15 03:17:15 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// request update motor speed
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write("?MBS\r\n");
|
2016-08-15 03:17:15 -03:00
|
|
|
_last_request_type = RequestType_MotorSpeed;
|
|
|
|
_last_request_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
|
|
|
|
// set spin direction of motor
|
2019-11-13 07:10:53 -04:00
|
|
|
void AP_Proximity_LightWareSF40C_v09::set_motor_direction()
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
|
|
|
// exit immediately if no uart
|
2019-12-04 00:59:07 -04:00
|
|
|
if (_uart == nullptr) {
|
2016-08-15 03:17:15 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set motor update speed
|
|
|
|
if (frontend.get_orientation(state.instance) == 0) {
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write("#MBD,0\r\n"); // spin clockwise
|
2016-08-15 03:17:15 -03:00
|
|
|
} else {
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write("#MBD,1\r\n"); // spin counter clockwise
|
2016-08-15 03:17:15 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// request update on motor direction
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write("?MBD\r\n");
|
2016-08-15 03:17:15 -03:00
|
|
|
_last_request_type = RequestType_MotorDirection;
|
|
|
|
_last_request_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
|
|
|
|
// set forward direction (to allow rotating lidar)
|
2019-11-13 07:10:53 -04:00
|
|
|
void AP_Proximity_LightWareSF40C_v09::set_forward_direction()
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
|
|
|
// exit immediately if no uart
|
2019-12-04 00:59:07 -04:00
|
|
|
if (_uart == nullptr) {
|
2016-08-15 03:17:15 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set forward direction
|
|
|
|
char request_str[15];
|
|
|
|
int16_t yaw_corr = frontend.get_yaw_correction(state.instance);
|
AP_Proximity: fix compilation warning in LightWare driver
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp: In member
function ‘void AP_Proximity_LightWareSF40C::request_new_data()’:
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:235:6:
warning:
‘__builtin___snprintf_chk’ output may be truncated before the last
format
character [-Wformat-truncation=]
void AP_Proximity_LightWareSF40C::request_new_data()
^~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /usr/include/stdio.h:862:0,
from ../../libraries/AP_Common/AP_Common.h:179,
from ../../libraries/AP_HAL/UARTDriver.h:5,
from ../../libraries/AP_HAL/HAL.h:11,
from ../../libraries/AP_HAL/AP_HAL_Main.h:19,
from ../../libraries/AP_HAL/AP_HAL.h:8,
from
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:16:
/usr/include/x86_64-linux-gnu/bits/stdio2.h:65:44: note:
‘__builtin___snprintf_chk’ output between 10 and 16 bytes into a
destination
of size 15
__bos (__s), __fmt, __va_arg_pack ());
^
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp: In member
function ‘bool
AP_Proximity_LightWareSF40C::send_request_for_distance()’:
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:275:6:
warning:
‘__builtin___snprintf_chk’ output may be truncated before the last
format
character [-Wformat-truncation=]
bool AP_Proximity_LightWareSF40C::send_request_for_distance()
^~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /usr/include/stdio.h:862:0,
from ../../libraries/AP_Common/AP_Common.h:179,
from ../../libraries/AP_HAL/UARTDriver.h:5,
from ../../libraries/AP_HAL/HAL.h:11,
from ../../libraries/AP_HAL/AP_HAL_Main.h:19,
from ../../libraries/AP_HAL/AP_HAL.h:8,
from
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:16:
/usr/include/x86_64-linux-gnu/bits/stdio2.h:65:44: note:
2018-01-25 08:00:22 -04:00
|
|
|
yaw_corr = constrain_int16(yaw_corr, -999, 999);
|
|
|
|
snprintf(request_str, sizeof(request_str), "#MBF,%d\r\n", yaw_corr);
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write(request_str);
|
2016-08-15 03:17:15 -03:00
|
|
|
|
|
|
|
// request update on motor direction
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write("?MBF\r\n");
|
2016-08-15 03:17:15 -03:00
|
|
|
_last_request_type = RequestType_ForwardDirection;
|
|
|
|
_last_request_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
|
|
|
|
// request new data if required
|
2019-11-13 07:10:53 -04:00
|
|
|
void AP_Proximity_LightWareSF40C_v09::request_new_data()
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
2019-12-04 00:59:07 -04:00
|
|
|
if (_uart == nullptr) {
|
2016-08-15 03:17:15 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// after timeout assume no reply will ever come
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
if ((_last_request_type != RequestType_None) && ((now - _last_request_ms) > PROXIMITY_SF40C_TIMEOUT_MS)) {
|
|
|
|
_last_request_type = RequestType_None;
|
|
|
|
_last_request_ms = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if we are not waiting for a reply, ask for something
|
|
|
|
if (_last_request_type == RequestType_None) {
|
|
|
|
_request_count++;
|
|
|
|
if (_request_count >= 5) {
|
|
|
|
send_request_for_health();
|
|
|
|
_request_count = 0;
|
|
|
|
} else {
|
|
|
|
// request new distance measurement
|
|
|
|
send_request_for_distance();
|
|
|
|
}
|
|
|
|
_last_request_ms = now;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// send request for sensor health
|
2019-11-13 07:10:53 -04:00
|
|
|
void AP_Proximity_LightWareSF40C_v09::send_request_for_health()
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
2019-12-04 00:59:07 -04:00
|
|
|
if (_uart == nullptr) {
|
2016-08-15 03:17:15 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write("?GS\r\n");
|
2016-08-15 03:17:15 -03:00
|
|
|
_last_request_type = RequestType_Health;
|
|
|
|
_last_request_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
|
|
|
|
// send request for distance from the next sector
|
2019-11-13 07:10:53 -04:00
|
|
|
bool AP_Proximity_LightWareSF40C_v09::send_request_for_distance()
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
2019-12-04 00:59:07 -04:00
|
|
|
if (_uart == nullptr) {
|
2016-08-15 03:17:15 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// increment sector
|
|
|
|
_last_sector++;
|
2019-12-03 22:46:03 -04:00
|
|
|
if (_last_sector >= PROXIMITY_NUM_SECTORS) {
|
2016-08-15 03:17:15 -03:00
|
|
|
_last_sector = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// prepare request
|
2018-03-16 17:02:30 -03:00
|
|
|
char request_str[16];
|
AP_Proximity: fix compilation warning in LightWare driver
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp: In member
function ‘void AP_Proximity_LightWareSF40C::request_new_data()’:
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:235:6:
warning:
‘__builtin___snprintf_chk’ output may be truncated before the last
format
character [-Wformat-truncation=]
void AP_Proximity_LightWareSF40C::request_new_data()
^~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /usr/include/stdio.h:862:0,
from ../../libraries/AP_Common/AP_Common.h:179,
from ../../libraries/AP_HAL/UARTDriver.h:5,
from ../../libraries/AP_HAL/HAL.h:11,
from ../../libraries/AP_HAL/AP_HAL_Main.h:19,
from ../../libraries/AP_HAL/AP_HAL.h:8,
from
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:16:
/usr/include/x86_64-linux-gnu/bits/stdio2.h:65:44: note:
‘__builtin___snprintf_chk’ output between 10 and 16 bytes into a
destination
of size 15
__bos (__s), __fmt, __va_arg_pack ());
^
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp: In member
function ‘bool
AP_Proximity_LightWareSF40C::send_request_for_distance()’:
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:275:6:
warning:
‘__builtin___snprintf_chk’ output may be truncated before the last
format
character [-Wformat-truncation=]
bool AP_Proximity_LightWareSF40C::send_request_for_distance()
^~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /usr/include/stdio.h:862:0,
from ../../libraries/AP_Common/AP_Common.h:179,
from ../../libraries/AP_HAL/UARTDriver.h:5,
from ../../libraries/AP_HAL/HAL.h:11,
from ../../libraries/AP_HAL/AP_HAL_Main.h:19,
from ../../libraries/AP_HAL/AP_HAL.h:8,
from
../../libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp:16:
/usr/include/x86_64-linux-gnu/bits/stdio2.h:65:44: note:
2018-01-25 08:00:22 -04:00
|
|
|
snprintf(request_str, sizeof(request_str), "?TS,%u,%u\r\n",
|
2019-12-03 22:46:03 -04:00
|
|
|
(unsigned int)PROXIMITY_SECTOR_WIDTH_DEG,
|
2020-12-06 08:23:55 -04:00
|
|
|
boundary._sector_middle_deg[_last_sector]);
|
2019-12-04 00:59:07 -04:00
|
|
|
_uart->write(request_str);
|
2016-08-15 03:17:15 -03:00
|
|
|
|
|
|
|
|
|
|
|
// record request for distance
|
|
|
|
_last_request_type = RequestType_DistanceMeasurement;
|
|
|
|
_last_request_ms = AP_HAL::millis();
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for replies from sensor, returns true if at least one message was processed
|
2019-11-13 07:10:53 -04:00
|
|
|
bool AP_Proximity_LightWareSF40C_v09::check_for_reply()
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
2019-12-04 00:59:07 -04:00
|
|
|
if (_uart == nullptr) {
|
2016-08-15 03:17:15 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// read any available lines from the lidar
|
|
|
|
// if CR (i.e. \r), LF (\n) it means we have received a full packet so send for processing
|
|
|
|
// lines starting with # are ignored because this is the echo of a set-motor request which has no reply
|
|
|
|
// lines starting with ? are the echo back of our distance request followed by the sensed distance
|
|
|
|
// distance data appears after a <space>
|
|
|
|
// distance data is comma separated so we put into separate elements (i.e. <space>angle,distance)
|
|
|
|
uint16_t count = 0;
|
2019-12-04 00:59:07 -04:00
|
|
|
int16_t nbytes = _uart->available();
|
2016-08-15 03:17:15 -03:00
|
|
|
while (nbytes-- > 0) {
|
2019-12-04 00:59:07 -04:00
|
|
|
char c = _uart->read();
|
2016-08-15 03:17:15 -03:00
|
|
|
// check for end of packet
|
|
|
|
if (c == '\r' || c == '\n') {
|
|
|
|
if ((element_len[0] > 0)) {
|
|
|
|
if (process_reply()) {
|
|
|
|
count++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
// clear buffers after processing
|
|
|
|
clear_buffers();
|
|
|
|
ignore_reply = false;
|
|
|
|
wait_for_space = false;
|
|
|
|
|
|
|
|
// if message starts with # ignore it
|
|
|
|
} else if (c == '#' || ignore_reply) {
|
|
|
|
ignore_reply = true;
|
|
|
|
|
|
|
|
// if waiting for <space>
|
|
|
|
} else if (c == '?') {
|
|
|
|
wait_for_space = true;
|
|
|
|
|
|
|
|
} else if (wait_for_space) {
|
|
|
|
if (c == ' ') {
|
|
|
|
wait_for_space = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if comma, move onto filling in 2nd element
|
|
|
|
} else if (c == ',') {
|
|
|
|
if ((element_num == 0) && (element_len[0] > 0)) {
|
|
|
|
element_num++;
|
|
|
|
} else {
|
|
|
|
// don't support 3rd element so clear buffers
|
|
|
|
clear_buffers();
|
|
|
|
ignore_reply = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if part of a number, add to element buffer
|
|
|
|
} else if (isdigit(c) || c == '.' || c == '-') {
|
|
|
|
element_buf[element_num][element_len[element_num]] = c;
|
|
|
|
element_len[element_num]++;
|
|
|
|
if (element_len[element_num] >= sizeof(element_buf[element_num])-1) {
|
|
|
|
// too long, discard the line
|
|
|
|
clear_buffers();
|
|
|
|
ignore_reply = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return (count > 0);
|
|
|
|
}
|
|
|
|
|
|
|
|
// process reply
|
2019-11-13 07:10:53 -04:00
|
|
|
bool AP_Proximity_LightWareSF40C_v09::process_reply()
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
2019-12-04 00:59:07 -04:00
|
|
|
if (_uart == nullptr) {
|
2016-08-15 03:17:15 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool success = false;
|
|
|
|
|
|
|
|
switch (_last_request_type) {
|
|
|
|
case RequestType_None:
|
|
|
|
break;
|
|
|
|
|
|
|
|
case RequestType_Health:
|
|
|
|
// expect result in the form "0xhhhh"
|
|
|
|
if (element_len[0] > 0) {
|
2019-08-01 02:08:14 -03:00
|
|
|
long int result = strtol(element_buf[0], nullptr, 16);
|
|
|
|
if (result > 0) {
|
2016-08-15 03:17:15 -03:00
|
|
|
_sensor_status.value = result;
|
|
|
|
success = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case RequestType_MotorSpeed:
|
|
|
|
_motor_speed = atoi(element_buf[0]);
|
|
|
|
success = true;
|
|
|
|
break;
|
|
|
|
|
|
|
|
case RequestType_MotorDirection:
|
|
|
|
_motor_direction = atoi(element_buf[0]);
|
|
|
|
success = true;
|
|
|
|
break;
|
|
|
|
|
|
|
|
case RequestType_ForwardDirection:
|
|
|
|
_forward_direction = atoi(element_buf[0]);
|
|
|
|
success = true;
|
|
|
|
break;
|
|
|
|
|
|
|
|
case RequestType_DistanceMeasurement:
|
|
|
|
{
|
2019-10-27 08:51:45 -03:00
|
|
|
float angle_deg = strtof(element_buf[0], NULL);
|
|
|
|
float distance_m = strtof(element_buf[1], NULL);
|
2021-02-19 14:55:28 -04:00
|
|
|
if (!ignore_reading(angle_deg, distance_m)) {
|
2016-08-15 03:17:15 -03:00
|
|
|
_last_distance_received_ms = AP_HAL::millis();
|
|
|
|
success = true;
|
2020-12-06 08:23:55 -04:00
|
|
|
// Get location on 3-D boundary based on angle to the object
|
2020-12-14 03:58:13 -04:00
|
|
|
const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg);
|
2020-12-06 08:23:55 -04:00
|
|
|
if (is_positive(distance_m)) {
|
2020-12-14 03:58:13 -04:00
|
|
|
boundary.set_face_attributes(face, angle_deg, distance_m);
|
2020-12-06 08:23:55 -04:00
|
|
|
// update OA database
|
|
|
|
database_push(angle_deg, distance_m);
|
2020-12-14 03:58:13 -04:00
|
|
|
} else {
|
|
|
|
// invalidate distance of face
|
|
|
|
boundary.reset_face(face);
|
2020-12-06 08:23:55 -04:00
|
|
|
}
|
2016-08-15 03:17:15 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
default:
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// mark request as cleared
|
|
|
|
if (success) {
|
|
|
|
_last_request_type = RequestType_None;
|
|
|
|
}
|
|
|
|
|
|
|
|
return success;
|
|
|
|
}
|
|
|
|
|
|
|
|
// clear buffers ahead of processing next message
|
2019-11-13 07:10:53 -04:00
|
|
|
void AP_Proximity_LightWareSF40C_v09::clear_buffers()
|
2016-08-15 03:17:15 -03:00
|
|
|
{
|
|
|
|
element_len[0] = 0;
|
|
|
|
element_len[1] = 0;
|
|
|
|
element_num = 0;
|
|
|
|
memset(element_buf, 0, sizeof(element_buf));
|
|
|
|
}
|
2021-03-25 04:32:09 -03:00
|
|
|
|
|
|
|
#endif // HAL_PROXIMITY_ENABLED
|