mirror of https://github.com/ArduPilot/ardupilot
Rover: support a 2nd GPS
This commit is contained in:
parent
07826096a2
commit
82ffc0ff2b
|
@ -195,6 +195,9 @@ static bool in_log_download;
|
||||||
|
|
||||||
// All GPS access should be through this pointer.
|
// All GPS access should be through this pointer.
|
||||||
static GPS *g_gps;
|
static GPS *g_gps;
|
||||||
|
#if GPS2_ENABLE
|
||||||
|
static GPS *g_gps2;
|
||||||
|
#endif
|
||||||
|
|
||||||
// flight modes convenience array
|
// flight modes convenience array
|
||||||
static AP_Int8 *modes = &g.mode1;
|
static AP_Int8 *modes = &g.mode1;
|
||||||
|
@ -216,6 +219,9 @@ static AP_Compass_HIL compass;
|
||||||
// GPS selection
|
// GPS selection
|
||||||
#if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
|
#if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
|
||||||
AP_GPS_Auto g_gps_driver(&g_gps);
|
AP_GPS_Auto g_gps_driver(&g_gps);
|
||||||
|
#if GPS2_ENABLE
|
||||||
|
AP_GPS_UBLOX g_gps2_driver;
|
||||||
|
#endif
|
||||||
|
|
||||||
#elif GPS_PROTOCOL == GPS_PROTOCOL_NMEA
|
#elif GPS_PROTOCOL == GPS_PROTOCOL_NMEA
|
||||||
AP_GPS_NMEA g_gps_driver;
|
AP_GPS_NMEA g_gps_driver;
|
||||||
|
@ -820,6 +826,19 @@ static void update_GPS_50Hz(void)
|
||||||
static uint32_t last_gps_reading;
|
static uint32_t last_gps_reading;
|
||||||
g_gps->update();
|
g_gps->update();
|
||||||
|
|
||||||
|
#if GPS2_ENABLE
|
||||||
|
static uint32_t last_gps2_reading;
|
||||||
|
if (g_gps2 != NULL) {
|
||||||
|
g_gps2->update();
|
||||||
|
if (g_gps2->last_message_time_ms() != last_gps2_reading) {
|
||||||
|
last_gps2_reading = g_gps2->last_message_time_ms();
|
||||||
|
if (g.log_bitmask & MASK_LOG_GPS) {
|
||||||
|
DataFlash.Log_Write_GPS2(g_gps2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (g_gps->last_message_time_ms() != last_gps_reading) {
|
if (g_gps->last_message_time_ms() != last_gps_reading) {
|
||||||
last_gps_reading = g_gps->last_message_time_ms();
|
last_gps_reading = g_gps->last_message_time_ms();
|
||||||
if (should_log(MASK_LOG_GPS)) {
|
if (should_log(MASK_LOG_GPS)) {
|
||||||
|
|
|
@ -242,6 +242,28 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
||||||
g_gps->ground_speed_cm, // cm/s
|
g_gps->ground_speed_cm, // cm/s
|
||||||
g_gps->ground_course_cd, // 1/100 degrees,
|
g_gps->ground_course_cd, // 1/100 degrees,
|
||||||
g_gps->num_sats);
|
g_gps->num_sats);
|
||||||
|
|
||||||
|
#if GPS2_ENABLE
|
||||||
|
if (g_gps2 != NULL) {
|
||||||
|
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||||
|
if (payload_space >= MAVLINK_MSG_ID_GPS2_RAW_LEN) {
|
||||||
|
mavlink_msg_gps2_raw_send(
|
||||||
|
chan,
|
||||||
|
g_gps2->last_fix_time*(uint64_t)1000,
|
||||||
|
g_gps2->status(),
|
||||||
|
g_gps2->latitude, // in 1E7 degrees
|
||||||
|
g_gps2->longitude, // in 1E7 degrees
|
||||||
|
g_gps2->altitude_cm * 10, // in mm
|
||||||
|
g_gps2->hdop,
|
||||||
|
65535,
|
||||||
|
g_gps2->ground_speed_cm, // cm/s
|
||||||
|
g_gps2->ground_course_cd, // 1/100 degrees,
|
||||||
|
g_gps2->num_sats,
|
||||||
|
0,
|
||||||
|
0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void NOINLINE send_system_time(mavlink_channel_t chan)
|
static void NOINLINE send_system_time(mavlink_channel_t chan)
|
||||||
|
|
|
@ -100,6 +100,12 @@
|
||||||
# define CURRENT_PIN_1 -1
|
# define CURRENT_PIN_1 -1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||||
|
#define GPS2_ENABLE 1
|
||||||
|
#else
|
||||||
|
#define GPS2_ENABLE 0
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// IMU Selection
|
// IMU Selection
|
||||||
//
|
//
|
||||||
|
|
|
@ -92,7 +92,13 @@ static void init_ardupilot()
|
||||||
// on the message set configured.
|
// on the message set configured.
|
||||||
//
|
//
|
||||||
// standard gps running
|
// standard gps running
|
||||||
hal.uartB->begin(115200, 256, 16);
|
hal.uartB->begin(38400, 256, 16);
|
||||||
|
|
||||||
|
#if GPS2_ENABLE
|
||||||
|
if (hal.uartE != NULL) {
|
||||||
|
hal.uartE->begin(38400, 256, 16);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
|
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
|
||||||
"\n\nFree RAM: %u\n"),
|
"\n\nFree RAM: %u\n"),
|
||||||
|
@ -185,6 +191,13 @@ static void init_ardupilot()
|
||||||
// GPS initialisation
|
// GPS initialisation
|
||||||
g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G);
|
g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G);
|
||||||
|
|
||||||
|
#if GPS2_ENABLE
|
||||||
|
if (hal.uartE != NULL) {
|
||||||
|
g_gps2 = &g_gps2_driver;
|
||||||
|
g_gps2->init(hal.uartE, GPS::GPS_ENGINE_AIRBORNE_4G);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
//mavlink_system.sysid = MAV_SYSTEM_ID; // Using g.sysid_this_mav
|
//mavlink_system.sysid = MAV_SYSTEM_ID; // Using g.sysid_this_mav
|
||||||
mavlink_system.compid = 1; //MAV_COMP_ID_IMU; // We do not check for comp id
|
mavlink_system.compid = 1; //MAV_COMP_ID_IMU; // We do not check for comp id
|
||||||
mavlink_system.type = MAV_TYPE_GROUND_ROVER;
|
mavlink_system.type = MAV_TYPE_GROUND_ROVER;
|
||||||
|
|
Loading…
Reference in New Issue