mirror of https://github.com/ArduPilot/ardupilot
Copter: added OpenDroneID support
This commit is contained in:
parent
0cc5c411ba
commit
0a64bc8cbc
|
@ -207,6 +207,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
#if OSD_ENABLED == ENABLED
|
||||
SCHED_TASK(publish_osd_info, 1, 10),
|
||||
#endif
|
||||
#if AP_OPENDRONEID_ENABLED
|
||||
SCHED_TASK_CLASS(AP_OpenDroneID, &copter.g2.opendroneid, update, 10, 50),
|
||||
#endif
|
||||
};
|
||||
|
||||
constexpr int8_t Copter::_failsafe_priorities[7];
|
||||
|
|
|
@ -67,6 +67,7 @@
|
|||
#include <AP_TempCalibration/AP_TempCalibration.h>
|
||||
#include <AC_AutoTune/AC_AutoTune.h>
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
#include <AP_OpenDroneID/AP_OpenDroneID.h>
|
||||
|
||||
// Configuration
|
||||
#include "defines.h"
|
||||
|
|
|
@ -961,7 +961,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
AP_SUBGROUPINFO(arot, "AROT_", 37, ParametersG2, AC_Autorotation),
|
||||
#endif
|
||||
|
||||
|
||||
#if AP_OPENDRONEID_ENABLED
|
||||
// @Group: DID_
|
||||
// @Path: ../libraries/AP_OpenDroneID/AP_OpenDroneID.cpp
|
||||
AP_SUBGROUPINFO(opendroneid, "DID_", 60, ParametersG2, AP_OpenDroneID),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
|
@ -620,6 +620,10 @@ public:
|
|||
// Autonmous autorotation
|
||||
AC_Autorotation arot;
|
||||
#endif
|
||||
|
||||
#if AP_OPENDRONEID_ENABLED
|
||||
AP_OpenDroneID opendroneid;
|
||||
#endif
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
|
|
@ -257,6 +257,10 @@ void Copter::init_ardupilot()
|
|||
// disable safety if requested
|
||||
BoardConfig.init_safety();
|
||||
|
||||
#if AP_OPENDRONEID_ENABLED
|
||||
g2.opendroneid.init();
|
||||
#endif
|
||||
|
||||
vehicle_setup();
|
||||
|
||||
hal.console->printf("\nReady to FLY ");
|
||||
|
|
Loading…
Reference in New Issue