AP_vehicle: added support for frsky bidirectional telemetry
This commit is contained in:
parent
988af83fce
commit
0012b83d86
@ -3,6 +3,7 @@
|
||||
#include <AP_BLHeli/AP_BLHeli.h>
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
#include <AP_Arming/AP_Arming.h>
|
||||
#include <AP_Frsky_Telem/AP_Frsky_Parameters.h>
|
||||
|
||||
#define SCHED_TASK(func, rate_hz, max_time_micros) SCHED_TASK_CLASS(AP_Vehicle, &vehicle, func, rate_hz, max_time_micros)
|
||||
|
||||
@ -27,7 +28,6 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
|
||||
// @Path: ../AP_VisualOdom/AP_VisualOdom.cpp
|
||||
AP_SUBGROUPINFO(visual_odom, "VISO", 3, AP_Vehicle, AP_VisualOdom),
|
||||
#endif
|
||||
|
||||
// @Group: VTX_
|
||||
// @Path: ../AP_RCTelemetry/AP_VideoTX.cpp
|
||||
AP_SUBGROUPINFO(vtx, "VTX_", 4, AP_Vehicle, AP_VideoTX),
|
||||
@ -38,6 +38,12 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
|
||||
AP_SUBGROUPINFO(msp, "MSP", 5, AP_Vehicle, AP_MSP),
|
||||
#endif
|
||||
|
||||
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
|
||||
// @Group: FRSKY_
|
||||
// @Path: ../AP_Frsky_Telem/AP_Frsky_Parameters.cpp
|
||||
AP_SUBGROUPINFO(frsky_parameters, "FRSKY_", 6, AP_Vehicle, AP_Frsky_Parameters),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -43,6 +43,7 @@
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
#include <AP_RCTelemetry/AP_VideoTX.h>
|
||||
#include <AP_MSP/AP_MSP.h>
|
||||
#include <AP_Frsky_Telem/AP_Frsky_Parameters.h>
|
||||
|
||||
class AP_Vehicle : public AP_HAL::HAL::Callbacks {
|
||||
|
||||
@ -213,6 +214,10 @@ public:
|
||||
// and flashing LEDs as appropriate
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
|
||||
AP_Frsky_Parameters frsky_parameters;
|
||||
#endif
|
||||
|
||||
protected:
|
||||
|
||||
virtual void init_ardupilot() = 0;
|
||||
|
@ -59,4 +59,5 @@ enum class ModeReason : uint8_t {
|
||||
RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL,
|
||||
RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND,
|
||||
MISSION_CMD,
|
||||
FRSKY_COMMAND,
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user