mirror of https://github.com/ArduPilot/ardupilot
Plane: updates for GPS changes
This commit is contained in:
parent
193a225887
commit
e8b9f22b01
|
@ -110,7 +110,6 @@ enum ChannelMixing {
|
||||||
// of these then existing logs will break! Only add at the end, and
|
// of these then existing logs will break! Only add at the end, and
|
||||||
// mark unused ones as 'deprecated', but leave them in
|
// mark unused ones as 'deprecated', but leave them in
|
||||||
enum log_messages {
|
enum log_messages {
|
||||||
LOG_INDEX_MSG,
|
|
||||||
LOG_CTUN_MSG,
|
LOG_CTUN_MSG,
|
||||||
LOG_NTUN_MSG,
|
LOG_NTUN_MSG,
|
||||||
LOG_PERFORMANCE_MSG,
|
LOG_PERFORMANCE_MSG,
|
||||||
|
@ -128,8 +127,7 @@ enum log_messages {
|
||||||
LOG_SONAR_MSG,
|
LOG_SONAR_MSG,
|
||||||
LOG_COMPASS2_MSG,
|
LOG_COMPASS2_MSG,
|
||||||
LOG_ARM_DISARM_MSG,
|
LOG_ARM_DISARM_MSG,
|
||||||
LOG_AIRSPEED_MSG,
|
LOG_AIRSPEED_MSG
|
||||||
MAX_NUM_LOGS // always at the end
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#define MASK_LOG_ATTITUDE_FAST (1<<0)
|
#define MASK_LOG_ATTITUDE_FAST (1<<0)
|
||||||
|
|
|
@ -181,12 +181,12 @@ static void init_ardupilot()
|
||||||
// Do GPS init
|
// Do GPS init
|
||||||
g_gps = &g_gps_driver;
|
g_gps = &g_gps_driver;
|
||||||
// GPS Initialization
|
// GPS Initialization
|
||||||
g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G);
|
g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, &DataFlash);
|
||||||
|
|
||||||
#if GPS2_ENABLE
|
#if GPS2_ENABLE
|
||||||
if (hal.uartE != NULL) {
|
if (hal.uartE != NULL) {
|
||||||
g_gps2 = &g_gps2_driver;
|
g_gps2 = &g_gps2_driver;
|
||||||
g_gps2->init(hal.uartE, GPS::GPS_ENGINE_AIRBORNE_4G);
|
g_gps2->init(hal.uartE, GPS::GPS_ENGINE_AIRBORNE_4G, &DataFlash);
|
||||||
g_gps2->set_secondary();
|
g_gps2->set_secondary();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue