mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-20 06:43:56 -04:00
AP_RangeFinder: use AP_SerialManager singleton
This commit is contained in:
parent
38e303389b
commit
ac96461c6c
@ -53,10 +53,10 @@
|
||||
*/
|
||||
AP_RangeFinder_BLPing::AP_RangeFinder_BLPing(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
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));
|
||||
@ -64,9 +64,9 @@ AP_RangeFinder_BLPing::AP_RangeFinder_BLPing(RangeFinder::RangeFinder_State &_st
|
||||
}
|
||||
|
||||
// detect if a serial port has been setup to accept rangefinder input
|
||||
bool AP_RangeFinder_BLPing::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
bool AP_RangeFinder_BLPing::detect(uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -11,11 +11,10 @@ public:
|
||||
// constructor
|
||||
AP_RangeFinder_BLPing(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance);
|
||||
|
||||
// static detection function
|
||||
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
|
||||
static bool detect(uint8_t serial_instance);
|
||||
|
||||
// update state
|
||||
void update(void) override;
|
||||
|
@ -50,12 +50,12 @@ extern const AP_HAL::HAL& hal;
|
||||
*/
|
||||
AP_RangeFinder_Benewake::AP_RangeFinder_Benewake(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance,
|
||||
benewake_model_type model) :
|
||||
AP_RangeFinder_Backend(_state, _params),
|
||||
model_type(model)
|
||||
{
|
||||
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));
|
||||
@ -67,9 +67,9 @@ AP_RangeFinder_Benewake::AP_RangeFinder_Benewake(RangeFinder::RangeFinder_State
|
||||
trying to take a reading on Serial. If we get a result the sensor is
|
||||
there.
|
||||
*/
|
||||
bool AP_RangeFinder_Benewake::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
bool AP_RangeFinder_Benewake::detect(uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
// distance returned in reading_cm, signal_ok is set to true if sensor reports a strong signal
|
||||
|
@ -16,12 +16,11 @@ public:
|
||||
// constructor
|
||||
AP_RangeFinder_Benewake(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance,
|
||||
benewake_model_type model);
|
||||
|
||||
// static detection function
|
||||
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
|
||||
static bool detect(uint8_t serial_instance);
|
||||
|
||||
// update state
|
||||
void update(void) override;
|
||||
|
@ -27,10 +27,10 @@ extern const AP_HAL::HAL& hal;
|
||||
*/
|
||||
AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
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));
|
||||
@ -42,9 +42,9 @@ AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_Stat
|
||||
trying to take a reading on Serial. If we get a result the sensor is
|
||||
there.
|
||||
*/
|
||||
bool AP_RangeFinder_LeddarOne::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
bool AP_RangeFinder_LeddarOne::detect(uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
// read - return last value measured by sensor
|
||||
|
@ -44,11 +44,10 @@ public:
|
||||
// constructor
|
||||
AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance);
|
||||
|
||||
// static detection function
|
||||
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
|
||||
static bool detect(uint8_t serial_instance);
|
||||
|
||||
// update state
|
||||
void update(void) override;
|
||||
|
@ -27,10 +27,10 @@ extern const AP_HAL::HAL& hal;
|
||||
*/
|
||||
AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
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));
|
||||
@ -42,9 +42,9 @@ AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder::Rang
|
||||
trying to take a reading on Serial. If we get a result the sensor is
|
||||
there.
|
||||
*/
|
||||
bool AP_RangeFinder_LightWareSerial::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
bool AP_RangeFinder_LightWareSerial::detect(uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
// read - return last value measured by sensor
|
||||
|
@ -10,11 +10,10 @@ public:
|
||||
// constructor
|
||||
AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance);
|
||||
|
||||
// static detection function
|
||||
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
|
||||
static bool detect(uint8_t serial_instance);
|
||||
|
||||
// update state
|
||||
void update(void) override;
|
||||
|
@ -31,10 +31,10 @@ extern const AP_HAL::HAL& hal;
|
||||
*/
|
||||
AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
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));
|
||||
@ -46,9 +46,9 @@ AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder::Ra
|
||||
trying to take a reading on Serial. If we get a result the sensor is
|
||||
there.
|
||||
*/
|
||||
bool AP_RangeFinder_MaxsonarSerialLV::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
bool AP_RangeFinder_MaxsonarSerialLV::detect(uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
// read - return last value measured by sensor
|
||||
|
@ -10,11 +10,10 @@ public:
|
||||
// constructor
|
||||
AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance);
|
||||
|
||||
// static detection function
|
||||
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
|
||||
static bool detect(uint8_t serial_instance);
|
||||
|
||||
// update state
|
||||
void update(void) override;
|
||||
|
@ -26,11 +26,11 @@ extern const AP_HAL::HAL& hal;
|
||||
// already know that we should setup the rangefinder
|
||||
AP_RangeFinder_NMEA::AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance) :
|
||||
AP_RangeFinder_Backend(_state, _params),
|
||||
_distance_m(-1.0f)
|
||||
{
|
||||
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));
|
||||
@ -38,9 +38,9 @@ AP_RangeFinder_NMEA::AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
|
||||
}
|
||||
|
||||
// detect if a NMEA rangefinder by looking to see if the user has configured it
|
||||
bool AP_RangeFinder_NMEA::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
bool AP_RangeFinder_NMEA::detect(uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
// update the state of the sensor
|
||||
|
@ -25,11 +25,10 @@ public:
|
||||
// constructor
|
||||
AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance);
|
||||
|
||||
// static detection function
|
||||
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
|
||||
static bool detect(uint8_t serial_instance);
|
||||
|
||||
// update state
|
||||
void update(void) override;
|
||||
|
@ -68,11 +68,11 @@ const AP_Param::GroupInfo AP_RangeFinder_Wasp::var_info[] = {
|
||||
|
||||
AP_RangeFinder_Wasp::AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance) :
|
||||
AP_RangeFinder_Backend(_state, _params) {
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
const AP_SerialManager &serial_manager = AP::serialmanager();
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
if (uart != nullptr) {
|
||||
uart->begin(115200);
|
||||
@ -85,8 +85,8 @@ AP_RangeFinder_Wasp::AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state,
|
||||
}
|
||||
|
||||
// detection is considered as locating a serial port
|
||||
bool AP_RangeFinder_Wasp::detect(AP_SerialManager &serial_manager, uint8_t serial_instance) {
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
bool AP_RangeFinder_Wasp::detect(uint8_t serial_instance) {
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
// read - return last value measured by sensor
|
||||
|
@ -11,10 +11,9 @@ class AP_RangeFinder_Wasp : public AP_RangeFinder_Backend {
|
||||
public:
|
||||
AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance);
|
||||
|
||||
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
|
||||
static bool detect(uint8_t serial_instance);
|
||||
|
||||
void update(void) override;
|
||||
|
||||
|
@ -34,11 +34,10 @@ extern const AP_HAL::HAL& hal;
|
||||
*/
|
||||
AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance) :
|
||||
AP_RangeFinder_Backend(_state, _params)
|
||||
{
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
if (uart != nullptr) {
|
||||
uart->begin(ULANDING_BAUD, ULANDING_BUFSIZE_RX, ULANDING_BUFSIZE_TX);
|
||||
}
|
||||
@ -49,9 +48,9 @@ AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State
|
||||
trying to take a reading on Serial. If we get a result the sensor is
|
||||
there.
|
||||
*/
|
||||
bool AP_RangeFinder_uLanding::detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
|
||||
bool AP_RangeFinder_uLanding::detect(uint8_t serial_instance)
|
||||
{
|
||||
return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -10,11 +10,10 @@ public:
|
||||
// constructor
|
||||
AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
AP_SerialManager &serial_manager,
|
||||
uint8_t serial_instance);
|
||||
|
||||
// static detection function
|
||||
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
|
||||
static bool detect(uint8_t serial_instance);
|
||||
|
||||
// update state
|
||||
void update(void) override;
|
||||
|
@ -39,10 +39,11 @@
|
||||
#include "AP_RangeFinder_PWM.h"
|
||||
#include "AP_RangeFinder_BLPing.h"
|
||||
#include "AP_RangeFinder_UAVCAN.h"
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
@ -152,8 +153,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
|
||||
const AP_Param::GroupInfo *RangeFinder::backend_var_info[RANGEFINDER_MAX_INSTANCES];
|
||||
|
||||
RangeFinder::RangeFinder(AP_SerialManager &_serial_manager) :
|
||||
serial_manager(_serial_manager)
|
||||
RangeFinder::RangeFinder()
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
@ -440,18 +440,18 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
break;
|
||||
#endif
|
||||
case RangeFinder_TYPE_LWSER:
|
||||
if (AP_RangeFinder_LightWareSerial::detect(serial_manager, serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_LightWareSerial(state[instance], params[instance], serial_manager, serial_instance++);
|
||||
if (AP_RangeFinder_LightWareSerial::detect(serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_LightWareSerial(state[instance], params[instance], serial_instance++);
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_LEDDARONE:
|
||||
if (AP_RangeFinder_LeddarOne::detect(serial_manager, serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_LeddarOne(state[instance], params[instance], serial_manager, serial_instance++);
|
||||
if (AP_RangeFinder_LeddarOne::detect(serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_LeddarOne(state[instance], params[instance], serial_instance++);
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_ULANDING:
|
||||
if (AP_RangeFinder_uLanding::detect(serial_manager, serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_uLanding(state[instance], params[instance], serial_manager, serial_instance++);
|
||||
if (AP_RangeFinder_uLanding::detect(serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_uLanding(state[instance], params[instance], serial_instance++);
|
||||
}
|
||||
break;
|
||||
#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
|
||||
@ -468,8 +468,8 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_MBSER:
|
||||
if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_manager, serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(state[instance], params[instance], serial_manager, serial_instance++);
|
||||
if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(state[instance], params[instance], serial_instance++);
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_ANALOG:
|
||||
@ -479,23 +479,23 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_NMEA:
|
||||
if (AP_RangeFinder_NMEA::detect(serial_manager, serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_NMEA(state[instance], params[instance], serial_manager, serial_instance++);
|
||||
if (AP_RangeFinder_NMEA::detect(serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_NMEA(state[instance], params[instance], serial_instance++);
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_WASP:
|
||||
if (AP_RangeFinder_Wasp::detect(serial_manager, serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_Wasp(state[instance], params[instance], serial_manager, serial_instance++);
|
||||
if (AP_RangeFinder_Wasp::detect(serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_Wasp(state[instance], params[instance], serial_instance++);
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_BenewakeTF02:
|
||||
if (AP_RangeFinder_Benewake::detect(serial_manager, serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_manager, serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TF02);
|
||||
if (AP_RangeFinder_Benewake::detect(serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TF02);
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_BenewakeTFmini:
|
||||
if (AP_RangeFinder_Benewake::detect(serial_manager, serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_manager, serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TFmini);
|
||||
if (AP_RangeFinder_Benewake::detect(serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TFmini);
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_PWM:
|
||||
@ -504,8 +504,8 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_BLPing:
|
||||
if (AP_RangeFinder_BLPing::detect(serial_manager, serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_BLPing(state[instance], params[instance], serial_manager, serial_instance++);
|
||||
if (AP_RangeFinder_BLPing::detect(serial_instance)) {
|
||||
drivers[instance] = new AP_RangeFinder_BLPing(state[instance], params[instance], serial_instance++);
|
||||
}
|
||||
break;
|
||||
default:
|
||||
|
@ -17,7 +17,7 @@
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include "AP_RangeFinder_Params.h"
|
||||
|
||||
// Maximum number of range finder instances available on this platform
|
||||
@ -38,7 +38,7 @@ class RangeFinder
|
||||
//UAVCAN drivers are initialised in the Backend, hence list of drivers is needed there.
|
||||
friend class AP_RangeFinder_UAVCAN;
|
||||
public:
|
||||
RangeFinder(AP_SerialManager &_serial_manager);
|
||||
RangeFinder();
|
||||
|
||||
/* Do not allow copies */
|
||||
RangeFinder(const RangeFinder &other) = delete;
|
||||
@ -166,7 +166,6 @@ private:
|
||||
AP_RangeFinder_Backend *drivers[RANGEFINDER_MAX_INSTANCES];
|
||||
uint8_t num_instances;
|
||||
float estimated_terrain_height;
|
||||
AP_SerialManager &serial_manager;
|
||||
Vector3f pos_offset_zero; // allows returning position offsets of zero for invalid requests
|
||||
|
||||
void convert_params(void);
|
||||
|
@ -11,7 +11,7 @@ void loop();
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
static AP_SerialManager serial_manager;
|
||||
static RangeFinder sonar{serial_manager};
|
||||
static RangeFinder sonar;
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user