Browse Source

AntennaTracker: build fixes for new GCS_MAVLink API

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
a3b91660eb
  1. 5
      Tools/AntennaTracker/GCS_Mavlink.pde
  2. 10
      Tools/AntennaTracker/system.pde

5
Tools/AntennaTracker/GCS_Mavlink.pde

@ -1062,8 +1062,9 @@ static void gcs_update(void) @@ -1062,8 +1062,9 @@ static void gcs_update(void)
}
}
// Also check for messages from the remote if we are in proxy mode
if (g.proxy_mode == true && proxy_vehicle.initialised)
proxy_vehicle.update();
if (g.proxy_mode == true && proxy_vehicle.initialised) {
proxy_vehicle.update(NULL);
}
}
static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)

10
Tools/AntennaTracker/system.pde

@ -35,12 +35,12 @@ static void init_tracker() @@ -35,12 +35,12 @@ static void init_tracker()
check_usb_mux();
// we have a 2nd serial port for telemetry
hal.uartC->begin(map_baudrate(g.serial1_baud, SERIAL1_BAUD),
128, SERIAL1_BUFSIZE);
if (g.proxy_mode == true)
proxy_vehicle.init(hal.uartC);
else
hal.uartC->begin(map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
if (g.proxy_mode == true) {
proxy_vehicle.setup_uart(hal.uartC, map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
} else {
gcs[1].setup_uart(hal.uartC, map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
}
mavlink_system.sysid = g.sysid_this_mav;

Loading…
Cancel
Save