mirror of https://github.com/ArduPilot/ardupilot
AP_ADSB: Allow for multiple backends in the future drivers
This commit is contained in:
parent
58c7f8279d
commit
e94697cb4c
|
@ -50,12 +50,12 @@ AP_ADSB *AP_ADSB::_singleton;
|
|||
|
||||
// table of user settable parameters
|
||||
const AP_Param::GroupInfo AP_ADSB::var_info[] = {
|
||||
// @Param: ENABLE
|
||||
// @DisplayName: Enable ADSB
|
||||
// @Description: Enable ADS-B
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @Param: TYPE
|
||||
// @DisplayName: ADSB Type
|
||||
// @Description: Type of ADS-B hardware for ADSB-in and ADSB-out configuration and operation. If any type is selected then MAVLink based ADSB-in messages will always be enabled
|
||||
// @Values: 0:Disabled,1:uAvionix-MAVLink
|
||||
// @User: Standard
|
||||
AP_GROUPINFO_FLAGS("ENABLE", 0, AP_ADSB, _enabled, 0, AP_PARAM_FLAG_ENABLE),
|
||||
AP_GROUPINFO_FLAGS("TYPE", 0, AP_ADSB, _type[0], 0, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
// index 1 is reserved - was BEHAVIOR
|
||||
|
||||
|
@ -194,17 +194,24 @@ void AP_ADSB::init(void)
|
|||
in_state.list_size_allocated = in_state.list_size_param;
|
||||
}
|
||||
|
||||
if (_backend == nullptr) {
|
||||
_backend = new AP_ADSB_uAvionix_MAVLink(*this);
|
||||
|
||||
if (_backend == nullptr) {
|
||||
_init_failed = true;
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB: Unable to initialize ADSB driver");
|
||||
return;
|
||||
if (detected_num_instances == 0) {
|
||||
for (uint8_t i=0; i<ADSB_MAX_INSTANCES; i++) {
|
||||
detect_instance(i);
|
||||
if (_backend[i] != nullptr) {
|
||||
// we loaded a driver for this instance, so it must be
|
||||
// present (although it may not be healthy)
|
||||
detected_num_instances = i+1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (detected_num_instances == 0) {
|
||||
_init_failed = true;
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB: Unable to initialize ADSB driver");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* de-initialize and free up some memory
|
||||
*/
|
||||
|
@ -214,11 +221,26 @@ void AP_ADSB::deinit(void)
|
|||
delete [] in_state.vehicle_list;
|
||||
in_state.vehicle_list = nullptr;
|
||||
}
|
||||
for (uint8_t i=0; i<ADSB_MAX_INSTANCES; i++) {
|
||||
if (_backend[i] != nullptr) {
|
||||
delete _backend[i];
|
||||
_backend[i] = nullptr;
|
||||
}
|
||||
}
|
||||
detected_num_instances = 0;
|
||||
}
|
||||
|
||||
bool AP_ADSB::check_startup()
|
||||
{
|
||||
if (!_enabled || _init_failed) {
|
||||
bool all_backends_disabled = true;
|
||||
for (uint8_t instance=0; instance<ADSB_MAX_INSTANCES; instance++) {
|
||||
if (_type[instance] > 0) {
|
||||
all_backends_disabled = false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (all_backends_disabled || _init_failed) {
|
||||
if (in_state.vehicle_list != nullptr) {
|
||||
deinit();
|
||||
}
|
||||
|
@ -231,6 +253,31 @@ bool AP_ADSB::check_startup()
|
|||
return in_state.vehicle_list != nullptr;
|
||||
}
|
||||
|
||||
|
||||
// detect if an instance of an ADSB sensor is connected.
|
||||
void AP_ADSB::detect_instance(uint8_t instance)
|
||||
{
|
||||
switch (get_type(instance)) {
|
||||
case Type::None:
|
||||
return;
|
||||
case Type::uAvionix_MAVLink:
|
||||
if (AP_ADSB_uAvionix_MAVLink::detect()) {
|
||||
_backend[instance] = new AP_ADSB_uAvionix_MAVLink(*this, instance);
|
||||
return;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// get instance type from instance
|
||||
AP_ADSB::Type AP_ADSB::get_type(uint8_t instance) const
|
||||
{
|
||||
if (instance < ADSB_MAX_INSTANCES) {
|
||||
return (Type)(_type[instance].get());
|
||||
}
|
||||
return Type::None;
|
||||
}
|
||||
|
||||
bool AP_ADSB::is_valid_callsign(uint16_t octal)
|
||||
{
|
||||
// treat "octal" as decimal and test if any decimal digit is > 7
|
||||
|
@ -311,9 +358,12 @@ void AP_ADSB::update(void)
|
|||
out_state.last_config_ms = 0; // send now
|
||||
}
|
||||
|
||||
if (_backend != nullptr) {
|
||||
_backend->update();
|
||||
for (uint8_t i=0; i<detected_num_instances; i++) {
|
||||
if (_backend[i] != nullptr) {
|
||||
_backend[i]->update();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -34,6 +34,8 @@
|
|||
#include <AP_Common/Location.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
#define ADSB_MAX_INSTANCES 1 // Maximum number of ADSB sensor instances available on this platform
|
||||
|
||||
class AP_ADSB_Backend;
|
||||
|
||||
class AP_ADSB {
|
||||
|
@ -53,6 +55,12 @@ public:
|
|||
return _singleton;
|
||||
}
|
||||
|
||||
// ADSB driver types
|
||||
enum class Type {
|
||||
None = 0,
|
||||
uAvionix_MAVLink = 1,
|
||||
};
|
||||
|
||||
struct adsb_vehicle_t {
|
||||
mavlink_adsb_vehicle_t info; // the whole mavlink struct with all the juicy details. sizeof() == 38
|
||||
uint32_t last_update_ms; // last time this was refreshed, allows timeouts
|
||||
|
@ -92,8 +100,14 @@ public:
|
|||
// extract a location out of a vehicle item
|
||||
Location get_location(const adsb_vehicle_t &vehicle) const;
|
||||
|
||||
// ADSB is considered enabled if there are any configured backends
|
||||
bool enabled() const {
|
||||
return _enabled;
|
||||
for (uint8_t instance=0; instance<detected_num_instances; instance++) {
|
||||
if (_type[instance] > 0) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool init_failed() const {
|
||||
|
@ -122,6 +136,8 @@ public:
|
|||
// confirm a value is a valid callsign
|
||||
static bool is_valid_callsign(uint16_t octal) WARN_IF_UNUSED;
|
||||
|
||||
AP_ADSB::Type get_type(uint8_t instance) const;
|
||||
|
||||
private:
|
||||
static AP_ADSB *_singleton;
|
||||
|
||||
|
@ -155,7 +171,9 @@ private:
|
|||
// mavlink handler
|
||||
void handle_transceiver_report(const mavlink_channel_t chan, const mavlink_uavionix_adsb_transceiver_health_report_t &packet);
|
||||
|
||||
AP_Int8 _enabled;
|
||||
void detect_instance(uint8_t instance);
|
||||
|
||||
AP_Int8 _type[ADSB_MAX_INSTANCES];
|
||||
|
||||
Location _my_loc;
|
||||
|
||||
|
@ -211,6 +229,7 @@ private:
|
|||
|
||||
} out_state;
|
||||
|
||||
uint8_t detected_num_instances;
|
||||
|
||||
// special ICAO of interest that ignored filters when != 0
|
||||
AP_Int32 _special_ICAO_target;
|
||||
|
@ -230,7 +249,7 @@ private:
|
|||
};
|
||||
|
||||
// reference to backend
|
||||
AP_ADSB_Backend *_backend;
|
||||
AP_ADSB_Backend *_backend[ADSB_MAX_INSTANCES];
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
|
|
@ -20,8 +20,9 @@
|
|||
/*
|
||||
base class constructor.
|
||||
*/
|
||||
AP_ADSB_Backend::AP_ADSB_Backend(AP_ADSB &frontend) :
|
||||
_frontend(frontend)
|
||||
AP_ADSB_Backend::AP_ADSB_Backend(AP_ADSB &frontend, uint8_t instance) :
|
||||
_frontend(frontend),
|
||||
_instance(instance)
|
||||
{
|
||||
}
|
||||
|
||||
|
|
|
@ -21,16 +21,21 @@ class AP_ADSB_Backend
|
|||
{
|
||||
public:
|
||||
// constructor.
|
||||
AP_ADSB_Backend(AP_ADSB &frontend);
|
||||
AP_ADSB_Backend(AP_ADSB &frontend, uint8_t instance);
|
||||
|
||||
// we declare a virtual destructor so that ADSB drivers can
|
||||
// override with a custom destructor if need be
|
||||
virtual ~AP_ADSB_Backend(void) {}
|
||||
|
||||
// static detection function
|
||||
static bool detect();
|
||||
|
||||
virtual void update() = 0;
|
||||
protected:
|
||||
|
||||
uint8_t _instance;
|
||||
|
||||
// references
|
||||
AP_ADSB &_frontend;
|
||||
|
||||
private:
|
||||
|
||||
};
|
||||
#endif // HAL_ADSB_ENABLED
|
||||
|
|
|
@ -15,7 +15,7 @@
|
|||
|
||||
#include "AP_ADSB_uAvionix_MAVLink.h"
|
||||
|
||||
#if HAL_ADSB_ENABLED
|
||||
#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED
|
||||
#include <stdio.h> // for sprintf
|
||||
#include <limits.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
@ -31,6 +31,14 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// detect if an port is configured as MAVLink
|
||||
bool AP_ADSB_uAvionix_MAVLink::detect()
|
||||
{
|
||||
// this actually requires SerialProtocol_MAVLink or SerialProtocol_MAVLink2 but
|
||||
// we can't have a running system with that, so its safe to assume it's already defined
|
||||
return true;
|
||||
}
|
||||
|
||||
void AP_ADSB_uAvionix_MAVLink::update()
|
||||
{
|
||||
const uint32_t now = AP_HAL::millis();
|
||||
|
|
|
@ -17,13 +17,20 @@
|
|||
|
||||
#include "AP_ADSB_Backend.h"
|
||||
|
||||
#if HAL_ADSB_ENABLED
|
||||
#ifndef HAL_ADSB_UAVIONIX_MAVLINK_ENABLED
|
||||
#define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED HAL_ADSB_ENABLED
|
||||
#endif
|
||||
|
||||
#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED
|
||||
class AP_ADSB_uAvionix_MAVLink : public AP_ADSB_Backend {
|
||||
public:
|
||||
using AP_ADSB_Backend::AP_ADSB_Backend;
|
||||
|
||||
void update() override;
|
||||
|
||||
// static detection function
|
||||
static bool detect();
|
||||
|
||||
private:
|
||||
// send static and dynamic data to ADSB transceiver
|
||||
void send_configure(const mavlink_channel_t chan);
|
||||
|
|
Loading…
Reference in New Issue