mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: add AP_NMEA_Output to Periph
This commit is contained in:
parent
9ac0514e8e
commit
95b4ded3e8
|
@ -245,6 +245,10 @@ void AP_Periph_FW::init()
|
||||||
temperature_sensor.init();
|
temperature_sensor.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_NMEA_OUTPUT_ENABLED
|
||||||
|
nmea.init();
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
||||||
notify.init();
|
notify.init();
|
||||||
#endif
|
#endif
|
||||||
|
@ -442,6 +446,10 @@ void AP_Periph_FW::update()
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_NMEA_OUTPUT_ENABLED
|
||||||
|
nmea.update();
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_TEMPERATURE_SENSOR_ENABLED
|
#if AP_TEMPERATURE_SENSOR_ENABLED
|
||||||
temperature_sensor.update();
|
temperature_sensor.update();
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -24,6 +24,13 @@
|
||||||
#include <AP_HAL/CANIface.h>
|
#include <AP_HAL/CANIface.h>
|
||||||
#include <AP_Stats/AP_Stats.h>
|
#include <AP_Stats/AP_Stats.h>
|
||||||
|
|
||||||
|
|
||||||
|
#include <AP_NMEA_Output/AP_NMEA_Output.h>
|
||||||
|
#if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && defined(HAL_PERIPH_ENABLE_GPS))
|
||||||
|
// Needs SerialManager + (AHRS or GPS)
|
||||||
|
#error "AP_NMEA_Output requires Serial/GCS and either AHRS or GPS. Needs HAL_GCS_ENABLED and HAL_PERIPH_ENABLE_GPS"
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAL_GCS_ENABLED
|
#if HAL_GCS_ENABLED
|
||||||
#include "GCS_MAVLink.h"
|
#include "GCS_MAVLink.h"
|
||||||
#endif
|
#endif
|
||||||
|
@ -128,6 +135,10 @@ public:
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_NMEA_OUTPUT_ENABLED
|
||||||
|
AP_NMEA_Output nmea;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_MAG
|
#ifdef HAL_PERIPH_ENABLE_MAG
|
||||||
Compass compass;
|
Compass compass;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -517,6 +517,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
||||||
GOBJECT(proximity, "PRX", AP_Proximity),
|
GOBJECT(proximity, "PRX", AP_Proximity),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_NMEA_OUTPUT_ENABLED
|
||||||
|
// @Group: NMEA_
|
||||||
|
// @Path: ../libraries/AP_NMEA_Output/AP_NMEA_Output.cpp
|
||||||
|
GOBJECT(nmea, "NMEA_", AP_NMEA_Output),
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_VAREND
|
AP_VAREND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -69,6 +69,7 @@ public:
|
||||||
k_param_proximity_baud,
|
k_param_proximity_baud,
|
||||||
k_param_proximity_port,
|
k_param_proximity_port,
|
||||||
k_param_proximity_max_rate,
|
k_param_proximity_max_rate,
|
||||||
|
k_param_nmea,
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_Int16 format_version;
|
AP_Int16 format_version;
|
||||||
|
|
|
@ -46,6 +46,7 @@ def build(bld):
|
||||||
'AP_SerialManager',
|
'AP_SerialManager',
|
||||||
'AP_RTC',
|
'AP_RTC',
|
||||||
'AP_Compass',
|
'AP_Compass',
|
||||||
|
'AP_NMEA_Output',
|
||||||
'AP_Baro',
|
'AP_Baro',
|
||||||
'Filter',
|
'Filter',
|
||||||
'AP_InternalError',
|
'AP_InternalError',
|
||||||
|
|
Loading…
Reference in New Issue