AP_Proximity: TeraRangerTower uses intermediate serial class

This commit is contained in:
Peter Barker 2019-12-04 16:02:27 +11:00 committed by Randy Mackay
parent 107c424a5c
commit 1190b9ff19
2 changed files with 7 additions and 38 deletions

View File

@ -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;
} }

View File

@ -1,19 +1,16 @@
#pragma once #pragma once
#include "AP_Proximity.h" #include "AP_Proximity.h"
#include "AP_Proximity_Backend.h" #include "AP_Proximity_Backend_Serial.h"
#define PROXIMITY_TRTOWER_TIMEOUT_MS 300 // requests timeout after 0.3 seconds #define PROXIMITY_TRTOWER_TIMEOUT_MS 300 // requests timeout after 0.3 seconds
class AP_Proximity_TeraRangerTower : public AP_Proximity_Backend class AP_Proximity_TeraRangerTower : public AP_Proximity_Backend_Serial
{ {
public: public:
// constructor
AP_Proximity_TeraRangerTower(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
// static detection function using AP_Proximity_Backend_Serial::AP_Proximity_Backend_Serial;
static bool detect();
// update state // update state
void update(void) override; void update(void) override;
@ -29,7 +26,6 @@ private:
void update_sector_data(int16_t angle_deg, uint16_t distance_cm); void update_sector_data(int16_t angle_deg, uint16_t distance_cm);
// reply related variables // reply related variables
AP_HAL::UARTDriver *uart = nullptr;
uint8_t buffer[20]; // buffer where to store data from serial uint8_t buffer[20]; // buffer where to store data from serial
uint8_t buffer_count; uint8_t buffer_count;