Skip to content

Commit

Permalink
AP_ADSB: add Sagetech driver
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Sep 15, 2020
1 parent 5055e64 commit e6b50f6
Show file tree
Hide file tree
Showing 8 changed files with 1,558 additions and 400 deletions.
552 changes: 208 additions & 344 deletions libraries/AP_ADSB/AP_ADSB.cpp

Large diffs are not rendered by default.

123 changes: 67 additions & 56 deletions libraries/AP_ADSB/AP_ADSB.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,34 @@
#include <AP_Common/Location.h>
#include <GCS_MAVLink/GCS_MAVLink.h>

#define ADSB_BITBASK_RF_CAPABILITIES_UAT_IN (1 << 0)
#define ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN (1 << 1)

class AP_ADSB_Backend;

class AP_ADSB {
public:
friend class AP_ADSB_Backend;

// constructor
AP_ADSB();

/* Do not allow copies */
AP_ADSB(const AP_ADSB &other) = delete;
AP_ADSB &operator=(const AP_ADSB&) = delete;

// get singleton instance
static AP_ADSB *get_singleton(void) {
return _singleton;
}

const char* GcsHeader = "ADSB: ";

enum class AP_ADSB_Protocol {
MAVLink = 0,
SAGETECH = 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
Expand All @@ -52,11 +71,16 @@ class AP_ADSB {
// send ADSB_VEHICLE mavlink message, usually as a StreamRate
void send_adsb_vehicle(mavlink_channel_t chan);

void set_stall_speed_cm(const uint16_t stall_speed_cm) { out_state.cfg.stall_speed_cm = stall_speed_cm; }
void set_stall_speed_cm(const uint16_t stall_speed_cm) {
if (!out_state.cfg.was_set_externally) {
out_state.cfg.stall_speed_cm = MAX(0,stall_speed_cm);
}
}

void set_max_speed(int16_t max_speed) {
if (!out_state.cfg.was_set_externally) {
// convert m/s to knots
out_state.cfg.maxAircraftSpeed_knots = (float)max_speed * 1.94384f;
out_state.cfg.maxAircraftSpeed_knots = (float)MAX(0,max_speed) * 1.94384f;
}
}

Expand Down Expand Up @@ -89,58 +113,6 @@ class AP_ADSB {
// confirm a value is a valid callsign
static bool is_valid_callsign(uint16_t octal) WARN_IF_UNUSED;

// get singleton instance
static AP_ADSB *get_singleton(void) {
return _singleton;
}

private:
static AP_ADSB *_singleton;

// initialize _vehicle_list
void init();

// free _vehicle_list
void deinit();

// compares current vector against vehicle_list to detect threats
void determine_furthest_aircraft(void);

// return index of given vehicle if ICAO_ADDRESS matches. return -1 if no match
bool find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const;

// remove a vehicle from the list
void delete_vehicle(const uint16_t index);

void set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle);

// Generates pseudorandom ICAO from gps time, lat, and lon
uint32_t genICAO(const Location &loc);

// set callsign: 8char string (plus null termination) then optionally append last 4 digits of icao
void set_callsign(const char* str, const bool append_icao);

// send static and dynamic data to ADSB transceiver
void send_configure(const mavlink_channel_t chan);
void send_dynamic_out(const mavlink_channel_t chan);

// special helpers for uAvionix workarounds
uint32_t get_encoded_icao(void);
uint8_t get_encoded_callsign_null_char(void);

// add or update vehicle_list from inbound mavlink msg
void handle_vehicle(const mavlink_message_t &msg);

// handle ADS-B transceiver report for ping2020
void handle_transceiver_report(mavlink_channel_t chan, const mavlink_message_t &msg);

void handle_out_cfg(const mavlink_message_t &msg);

AP_Int8 _enabled;

Location _my_loc;


// ADSB-IN state. Maintains list of external vehicles
struct {
// list management
Expand All @@ -161,8 +133,6 @@ class AP_ADSB {
struct {
uint32_t last_config_ms; // send once every 10s
uint32_t last_report_ms; // send at 5Hz
int8_t chan = -1; // channel that contains an ADS-b Transceiver. -1 means transceiver is not detected
uint32_t chan_last_ms;
UAVIONIX_ADSB_RF_HEALTH status; // transceiver status
bool is_flying;
bool _is_in_auto_mode;
Expand All @@ -188,6 +158,44 @@ class AP_ADSB {

} out_state;

AP_Int8 _enabled;

Location _my_loc;
AP_Int8 _type;

private:

static AP_ADSB *_singleton;

// initialize driver
void hw_init();

// free/load _vehicle_list
void list_init();
void list_deinit();

// compares current vector against vehicle_list to detect threats
void determine_furthest_aircraft(void);

// return index of given vehicle if ICAO_ADDRESS matches. return -1 if no match
bool find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const;

// remove a vehicle from the list
void delete_vehicle(const uint16_t index);

void set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle);

// Generates pseudorandom ICAO from gps time, lat, and lon
uint32_t genICAO(const Location &loc);

// set callsign: 8char string (plus null termination) then optionally append last 4 digits of icao
void set_callsign(const char* str, const bool append_icao);

// add or update vehicle_list from inbound mavlink msg
void handle_vehicle(const mavlink_message_t &msg);

// configure ADSB-out transceivers
void handle_out_cfg(const mavlink_uavionix_adsb_out_cfg_t &packet);

// index of and distance to furthest vehicle in list
uint16_t furthest_vehicle_index;
Expand All @@ -211,6 +219,9 @@ class AP_ADSB {
ALL = 2
};

// reference to backend
AP_ADSB_Backend *backend;


};

Expand Down
26 changes: 26 additions & 0 deletions libraries/AP_ADSB/AP_ADSB_Backend.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

#include "AP_ADSB_Backend.h"

/*
base class constructor.
This incorporates initialisation as well.
*/
AP_ADSB_Backend::AP_ADSB_Backend(AP_ADSB &_frontend) :
frontend(_frontend)
{
}

43 changes: 43 additions & 0 deletions libraries/AP_ADSB/AP_ADSB_Backend.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once

#include "AP_ADSB.h"

class AP_ADSB_Backend
{
public:
// constructor. This incorporates initialization as well.
AP_ADSB_Backend(AP_ADSB &_frontend);


virtual void init() = 0;

virtual void update() = 0;

// handle mavlink messages
virtual void handle_msg(const mavlink_channel_t chan, const mavlink_message_t &msg) {}
protected:

// references
AP_ADSB &frontend;


// semaphore for access to shared frontend data
//HAL_Semaphore _sem;

private:

};
Loading

0 comments on commit e6b50f6

Please sign in to comment.