mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: move AP_NMEA_OUTPUT to a first class library
This commit is contained in:
parent
ea35b28b22
commit
468d773391
|
@ -118,6 +118,12 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
|
|||
AP_SUBGROUPINFO(temperature_sensor, "TEMP", 16, AP_Vehicle, AP_TemperatureSensor),
|
||||
#endif
|
||||
|
||||
#if HAL_NMEA_OUTPUT_ENABLED
|
||||
// @Group: NMEA_
|
||||
// @Path: ../AP_NMEA_Output/AP_NMEA_Output.cpp
|
||||
AP_SUBGROUPINFO(nmea, "NMEA_", 17, AP_Vehicle, AP_NMEA_Output),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -274,6 +280,10 @@ void AP_Vehicle::setup()
|
|||
ais.init();
|
||||
#endif
|
||||
|
||||
#if HAL_NMEA_OUTPUT_ENABLED
|
||||
nmea.init();
|
||||
#endif
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
fence.init();
|
||||
#endif
|
||||
|
@ -359,6 +369,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
|
|||
#if COMPASS_CAL_ENABLED
|
||||
SCHED_TASK_CLASS(Compass, &vehicle.compass, cal_update, 100, 200, 75),
|
||||
#endif
|
||||
#if HAL_NMEA_OUTPUT_ENABLED
|
||||
SCHED_TASK_CLASS(AP_NMEA_Output, &vehicle.nmea, update, 50, 50, 180),
|
||||
#endif
|
||||
#if HAL_RUNCAM_ENABLED
|
||||
SCHED_TASK_CLASS(AP_RunCam, &vehicle.runcam, update, 50, 50, 200),
|
||||
#endif
|
||||
|
|
|
@ -55,6 +55,7 @@
|
|||
#include <SITL/SITL.h>
|
||||
#include <AP_CustomRotations/AP_CustomRotations.h>
|
||||
#include <AP_AIS/AP_AIS.h>
|
||||
#include <AP_NMEA_Output/AP_NMEA_Output.h>
|
||||
#include <AC_Fence/AC_Fence.h>
|
||||
#include <AP_CheckFirmware/AP_CheckFirmware.h>
|
||||
#include <Filter/LowPassFilter.h>
|
||||
|
@ -352,6 +353,10 @@ protected:
|
|||
AP_AIS ais;
|
||||
#endif
|
||||
|
||||
#if HAL_NMEA_OUTPUT_ENABLED
|
||||
AP_NMEA_Output nmea;
|
||||
#endif
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
AC_Fence fence;
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue