Tracker: snoop on all channels
This ensures we check for vehicle data on all channels
This commit is contained in:
parent
212e4940d4
commit
10b9f2ebe0
@ -23,10 +23,8 @@ static void init_tracker()
|
||||
// init baro before we start the GCS, so that the CLI baro test works
|
||||
barometer.init();
|
||||
|
||||
// init the GCS
|
||||
// init the GCS and start snooping for vehicle data
|
||||
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console, 0);
|
||||
|
||||
// set up snooping on other mavlink destinations
|
||||
gcs[0].set_snoop(mavlink_snoop);
|
||||
|
||||
// Register mavlink_delay_cb, which will run anytime you have
|
||||
@ -38,12 +36,14 @@ static void init_tracker()
|
||||
usb_connected = true;
|
||||
check_usb_mux();
|
||||
|
||||
// setup serial port for telem1
|
||||
// setup serial port for telem1 and start snooping for vehicle data
|
||||
gcs[1].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
||||
gcs[1].set_snoop(mavlink_snoop);
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
// setup serial port for telem2
|
||||
// setup serial port for telem2 and start snooping for vehicle data
|
||||
gcs[2].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 1);
|
||||
gcs[2].set_snoop(mavlink_snoop);
|
||||
#endif
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
Loading…
Reference in New Issue
Block a user