|
|
@ -15,43 +15,16 @@ |
|
|
|
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
#include "AP_Proximity_TeraRangerTower.h" |
|
|
|
#include "AP_Proximity_TeraRangerTower.h" |
|
|
|
#include <AP_SerialManager/AP_SerialManager.h> |
|
|
|
|
|
|
|
#include <AP_Math/crc.h> |
|
|
|
#include <AP_Math/crc.h> |
|
|
|
#include <ctype.h> |
|
|
|
#include <ctype.h> |
|
|
|
#include <stdio.h> |
|
|
|
#include <stdio.h> |
|
|
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
|
|
|
The constructor also initialises the proximity sensor. Note that this |
|
|
|
|
|
|
|
constructor is not called until detect() returns true, so we |
|
|
|
|
|
|
|
already know that we should setup the proximity sensor |
|
|
|
|
|
|
|
*/ |
|
|
|
|
|
|
|
AP_Proximity_TeraRangerTower::AP_Proximity_TeraRangerTower( |
|
|
|
|
|
|
|
AP_Proximity &_frontend, |
|
|
|
|
|
|
|
AP_Proximity::Proximity_State &_state) : |
|
|
|
|
|
|
|
AP_Proximity_Backend(_frontend, _state) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
const AP_SerialManager &serial_manager = AP::serialmanager(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0); |
|
|
|
|
|
|
|
if (uart != nullptr) { |
|
|
|
|
|
|
|
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar360, 0)); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// detect if a TeraRanger Tower proximity sensor is connected by looking for a configured serial port
|
|
|
|
|
|
|
|
bool AP_Proximity_TeraRangerTower::detect() |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
AP_HAL::UARTDriver *uart = nullptr; |
|
|
|
|
|
|
|
uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0); |
|
|
|
|
|
|
|
return uart != nullptr; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// update the state of the sensor
|
|
|
|
// update the state of the sensor
|
|
|
|
void AP_Proximity_TeraRangerTower::update(void) |
|
|
|
void AP_Proximity_TeraRangerTower::update(void) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (uart == nullptr) { |
|
|
|
if (_uart == nullptr) { |
|
|
|
return; |
|
|
|
return; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -79,15 +52,15 @@ float AP_Proximity_TeraRangerTower::distance_min() const |
|
|
|
// check for replies from sensor, returns true if at least one message was processed
|
|
|
|
// check for replies from sensor, returns true if at least one message was processed
|
|
|
|
bool AP_Proximity_TeraRangerTower::read_sensor_data() |
|
|
|
bool AP_Proximity_TeraRangerTower::read_sensor_data() |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (uart == nullptr) { |
|
|
|
if (_uart == nullptr) { |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
uint16_t message_count = 0; |
|
|
|
uint16_t message_count = 0; |
|
|
|
int16_t nbytes = uart->available(); |
|
|
|
int16_t nbytes = _uart->available(); |
|
|
|
|
|
|
|
|
|
|
|
while (nbytes-- > 0) { |
|
|
|
while (nbytes-- > 0) { |
|
|
|
char c = uart->read(); |
|
|
|
char c = _uart->read(); |
|
|
|
if (c == 'T' ) { |
|
|
|
if (c == 'T' ) { |
|
|
|
buffer_count = 0; |
|
|
|
buffer_count = 0; |
|
|
|
} |
|
|
|
} |
|
|
|