mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: make LeddarOne backend use new intermediate class
This commit is contained in:
parent
15d3a59d67
commit
ff7c5af437
|
@ -13,40 +13,13 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_RangeFinder_LeddarOne.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/crc.h>
|
||||
#include "AP_RangeFinder_LeddarOne.h"
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
||||
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_LeddarOne::AP_RangeFinder_LeddarOne(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 LeddarOne 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_LeddarOne::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_LeddarOne::get_reading(uint16_t &reading_cm)
|
||||
{
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include "RangeFinder.h"
|
||||
#include "RangeFinder_Backend.h"
|
||||
#include "RangeFinder_Backend_Serial.h"
|
||||
|
||||
// defines
|
||||
#define LEDDARONE_DEFAULT_ADDRESS 0x01
|
||||
|
@ -37,17 +37,12 @@ enum LeddarOne_ModbusStatus {
|
|||
LEDDARONE_MODBUS_STATE_AVAILABLE
|
||||
};
|
||||
|
||||
class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend
|
||||
class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend_Serial
|
||||
{
|
||||
|
||||
public:
|
||||
// constructor
|
||||
AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
uint8_t serial_instance);
|
||||
|
||||
// static detection function
|
||||
static bool detect(uint8_t serial_instance);
|
||||
using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial;
|
||||
|
||||
// update state
|
||||
void update(void) override;
|
||||
|
@ -68,7 +63,6 @@ private:
|
|||
// parse a response message from ModBus
|
||||
LeddarOne_Status parse_response(uint8_t &number_detections);
|
||||
|
||||
AP_HAL::UARTDriver *uart = nullptr;
|
||||
uint32_t last_sending_request_ms;
|
||||
uint32_t last_available_ms;
|
||||
|
||||
|
|
Loading…
Reference in New Issue