Skip to content

Commit

Permalink
Add --enable-overrid option
Browse files Browse the repository at this point in the history
- separated out the mac_eq function into a _utils file
- We can add more defines using --enable-overrid. The current one is
AP_ODIDSCANNER_ENABLED
  • Loading branch information
shipp02 committed Oct 31, 2024
1 parent aaa1325 commit 33d3d34
Show file tree
Hide file tree
Showing 12 changed files with 78 additions and 27 deletions.
11 changes: 10 additions & 1 deletion Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,15 @@ def srcpath(path):
else:
cfg.msg("Enabled OpenDroneID", 'no', color='YELLOW')

if cfg.options.enable_overrid:
env.ENABLE_OVERRID = True
env.DEFINES.update(
AP_ODIDSCANNER_ENABLED=1,
)
cfg.msg("Enabled uci-overRID", 'yes')
else:
cfg.msg("Enabled uci-overRID", 'no', color='YELLOW')

# allow enable of firmware ID checking for any board
if cfg.options.enable_check_firmware:
env.CHECK_FIRMWARE_ENABLED = True
Expand Down Expand Up @@ -1400,4 +1409,4 @@ class SITL_x86_64_linux_gnu(SITL_static):
toolchain = 'x86_64-linux-gnu'

class SITL_arm_linux_gnueabihf(SITL_static):
toolchain = 'arm-linux-gnueabihf'
toolchain = 'arm-linux-gnueabihf'
6 changes: 5 additions & 1 deletion libraries/AC_Avoidance/AP_OABendyRuler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,9 +451,11 @@ float AP_OABendyRuler::calc_avoidance_margin(const Location &start, const Locati
margin_min = MIN(margin_min, latest_margin);
}

#if AP_ODIDSCANNER_ENABLED
if (calc_margin_from_open_drone_id(start, end, latest_margin)) {
margin_min = MIN(margin_min, latest_margin);
}
#endif

// return smallest margin from any obstacle
return margin_min;
Expand Down Expand Up @@ -715,6 +717,7 @@ bool AP_OABendyRuler::calc_margin_from_object_database(const Location &start, co
return false;
}

#if AP_ODIDSCANNER_ENABLED
bool AP_OABendyRuler::calc_margin_from_open_drone_id(const Location &start, const Location &end, float &margin) const {
AP_ODIDScanner* odid = &AP::vehicle()->odidscanner;

Expand Down Expand Up @@ -745,4 +748,5 @@ bool AP_OABendyRuler::calc_margin_from_open_drone_id(const Location &start, cons
}

return false;
}
}
#endif
5 changes: 5 additions & 0 deletions libraries/AP_Avoidance/AP_Avoidance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ extern const AP_HAL::HAL& hal;
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_Logger/AP_Logger.h>
#include<AP_ODIDScanner/AP_ODIDScanner_utils.h>

#define AVOIDANCE_DEBUGGING 0

Expand Down Expand Up @@ -342,6 +343,7 @@ void AP_Avoidance::get_adsb_samples()

void AP_Avoidance::get_odid_samples()
{
#if AP_ODIDSCANNER_ENABLED
//TODO: Process samples here
// GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Avoidance: Get %d drones", AP::vehicle()->odidscanner.get_count());
for(int i = 0;i<AP::vehicle()->odidscanner.get_count();i++) {
Expand All @@ -359,6 +361,7 @@ void AP_Avoidance::get_odid_samples()
AP::vehicle()->odidscanner.get_vehicle_location(i),
vel);
}
#endif
}

float closest_approach_xy(const Location &my_loc,
Expand Down Expand Up @@ -639,9 +642,11 @@ void AP_Avoidance::update()
if (_adsb.enabled()) {
get_adsb_samples();
}
#if AP_ODIDSCANNER_ENABLED
if (AP::vehicle()->odidscanner.enabled()) {
get_odid_samples();
}
#endif

check_for_threats();

Expand Down
26 changes: 11 additions & 15 deletions libraries/AP_ODIDScanner/AP_ODIDScanner.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,7 @@
#include "AP_ODIDScanner.h"

#if AP_ODIDSCANNER_ENABLED

#include "GCS_MAVLink/GCS_MAVLink.h"
#include "GCS_MAVLink/GCS.h"
#include <AP_HAL/AP_HAL.h>
Expand All @@ -18,14 +21,6 @@
#define VEHICLE_TIMEOUT_MS 30000


bool mac_eq(uint8_t a[6], uint8_t b[6]) {
return a[0] == b[0] &&
a[1] == b[1] &&
a[2] == b[2] &&
a[3] == b[3] &&
a[4] == b[4] &&
a[5] == b[5];
}

// TODO: Random default for mav_port needs fix
AP_ODIDScanner::AP_ODIDScanner() : _mav_port(1){
Expand All @@ -37,11 +32,11 @@ bool AP_ODIDScanner::enabled() {
void AP_ODIDScanner::init() {
_chan = mavlink_channel_t(gcs().get_channel_from_port_number(_mav_port));
_initialised = true;
_port = AP::serialmanager().get_serial_by_id(_mav_port);
if (_port != nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scanner: Found RID Device");
_port->begin(57600, 512, 512);
}
/*_port = AP::serialmanager().get_serial_by_id(_mav_port);*/
/*if (_port != nullptr) {*/
/* GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scanner: Found RID Device");*/
/* _port->begin(57600, 512, 512);*/
/*}*/
}


Expand Down Expand Up @@ -92,7 +87,7 @@ void AP_ODIDScanner::update() {
last_dev_hb_msg_ms = now_ms;
// GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scanner: Device Not Found at %f",float(now_ms));
// this is a bug, the device is working when this is sent....
_port->printf("Scanner: Where is this printing?");
/*_port->printf("Scanner: Where is this printing?");*/
}

if (now_ms - last_hb_send_ms > 1000) { // why this?
Expand Down Expand Up @@ -251,4 +246,5 @@ rid_vehicle_t& AP_ODIDScanner::get_vehicle(int i) {
Location AP_ODIDScanner::get_vehicle_location(int i) {
auto v = this->get_vehicle(i);
return Location(v.loc.latitude, v.loc.longitude, v.loc.altitude_geodetic*100, Location::AltFrame::ABSOLUTE);
}
}
#endif // AP_ODIDSCANNER_ENABLED
18 changes: 12 additions & 6 deletions libraries/AP_ODIDScanner/AP_ODIDScanner.h
Original file line number Diff line number Diff line change
@@ -1,18 +1,24 @@

#pragma once

#include <cstdint>
#define ODID_SCANNER_ENABLED 1
#ifdef ODID_SCANNER_ENABLED
#ifndef AP_ODIDSCANNER_ENABLED
// default to off. Enabled in hwdef.dat
#define AP_ODIDSCANNER_ENABLED 0
#endif

#if AP_ODIDSCANNER_ENABLED
/*#include <cstdint>*/
/*#define ODID_SCANNER_ENABLED 1*/
/*#ifdef ODID_SCANNER_ENABLED*/

#include "AP_Common/AP_Common.h"
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Common/Location.h>
#include "AP_ODIDScanner_utils.h"

extern bool mac_eq(uint8_t a[6], uint8_t b[6]);


struct Loc : Location {
Expand Down Expand Up @@ -118,7 +124,7 @@ class AP_ODIDScanner

mavlink_uav_found_t found_msg;
mavlink_channel_t _chan;
AP_HAL::UARTDriver* _port;
/*AP_HAL::UARTDriver* _port;*/
bool _initialised;
uint32_t last_send_ms;
uint32_t last_dev_hb_ms;
Expand All @@ -133,4 +139,4 @@ class AP_ODIDScanner
};


#endif
#endif // AP_ODIDSCANNER_ENABLED
8 changes: 8 additions & 0 deletions libraries/AP_ODIDScanner/AP_ODIDScanner_config.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#pragma once

#include <AP_HAL/AP_HAL_Boards.h>

#ifndef AP_ODIDSCANNER_ENABLED
// default to off. Enabled in hwdef.dat
#define AP_ODIDSCANNER_ENABLED 1
#endif
10 changes: 10 additions & 0 deletions libraries/AP_ODIDScanner/AP_ODIDScanner_utils.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#include"AP_ODIDScanner_utils.h"

bool mac_eq(uint8_t a[6], uint8_t b[6]) {
return a[0] == b[0] &&
a[1] == b[1] &&
a[2] == b[2] &&
a[3] == b[3] &&
a[4] == b[4] &&
a[5] == b[5];
}
4 changes: 4 additions & 0 deletions libraries/AP_ODIDScanner/AP_ODIDScanner_utils.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
#pragma once
#include<cstdint>

bool mac_eq(uint8_t a[6], uint8_t b[6]);
6 changes: 5 additions & 1 deletion libraries/AP_Vehicle/AP_Vehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,7 +266,9 @@ void AP_Vehicle::setup()
#if AP_OPENDRONEID_ENABLED
opendroneid.init();
#endif
#if AP_ODIDSCANNER_ENABLED
odidscanner.init();
#endif

// init EFI monitoring
#if HAL_EFI_ENABLED
Expand Down Expand Up @@ -398,7 +400,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_OpenDroneID, &vehicle.opendroneid, update, 10, 50, 236),
#endif
// test comment...
#if AP_ODIDSCANNER_ENABLED
SCHED_TASK_CLASS(AP_ODIDScanner,&vehicle.odidscanner, update, 10, 50, 237),
#endif
#if OSD_ENABLED
SCHED_TASK(publish_osd_info, 1, 10, 240),
#endif
Expand Down Expand Up @@ -834,4 +838,4 @@ AP_Vehicle *vehicle()
return AP_Vehicle::get_singleton();
}

};
};
2 changes: 2 additions & 0 deletions libraries/AP_Vehicle/AP_Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -327,7 +327,9 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
AP_OpenDroneID opendroneid;
#endif
public:
#if AP_ODIDSCANNER_ENABLED
AP_ODIDScanner odidscanner;
#endif

#if HAL_MSP_ENABLED
AP_MSP msp;
Expand Down
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4016,7 +4016,7 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
#endif
break;

// #if AP_OPENDRONEID_ENABLED
#if AP_ODIDSCANNER_ENABLED
case MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS:
case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID:
case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID:
Expand All @@ -4032,10 +4032,10 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
AP::opendroneid().handle_msg(chan, msg);
}
break;
// #endif
case MAVLINK_MSG_ID_UAV_FOUND:
AP::vehicle()->odidscanner.handle_msg(msg);
break;
#endif

#if AP_SIGNED_FIRMWARE
case MAVLINK_MSG_ID_SECURE_COMMAND:
Expand Down
5 changes: 4 additions & 1 deletion wscript
Original file line number Diff line number Diff line change
Expand Up @@ -243,6 +243,9 @@ submodules at specific revisions.
g.add_option('--enable-opendroneid', action='store_true',
default=False,
help="Enables OpenDroneID")
g.add_option('--enable-overrid', action='store_true',
default=False,
help="Enables OpenDroneID")

g.add_option('--enable-check-firmware', action='store_true',
default=False,
Expand Down Expand Up @@ -895,4 +898,4 @@ class RsyncContext(LocalInstallContext):
if 'RSYNC_DEST' not in tg.env:
self.fatal('Destination for rsync not defined. Either pass --rsync-dest here or during configuration.')

tg.post()
tg.post()

0 comments on commit 33d3d34

Please sign in to comment.