mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
Tracker: add support for 4th mavlink channel
This commit is contained in:
parent
facbfaf31f
commit
35275aab85
@ -92,6 +92,7 @@ public:
|
||||
k_param_pitch_range,
|
||||
k_param_distance_min,
|
||||
k_param_sysid_target, // 138
|
||||
k_param_gcs3, // stream rates for fourth MAVLink port
|
||||
|
||||
//
|
||||
// 150: Telemetry control
|
||||
|
@ -222,6 +222,12 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GOBJECTN(gcs[2], gcs2, "SR2_", GCS_MAVLINK),
|
||||
#endif
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 3
|
||||
// @Group: SR3_
|
||||
// @Path: GCS_Mavlink.pde
|
||||
GOBJECTN(gcs[3], gcs3, "SR3_", GCS_MAVLINK),
|
||||
#endif
|
||||
|
||||
// @Group: INS_
|
||||
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
||||
GOBJECT(ins, "INS_", AP_InertialSensor),
|
||||
|
@ -46,6 +46,12 @@ static void init_tracker()
|
||||
gcs[2].set_snoop(mavlink_snoop);
|
||||
#endif
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 3
|
||||
// setup serial port for fourth telemetry port (not used by default) and start snooping for vehicle data
|
||||
gcs[3].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 2);
|
||||
gcs[3].set_snoop(mavlink_snoop);
|
||||
#endif
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
||||
if (g.compass_enabled==true) {
|
||||
|
Loading…
Reference in New Issue
Block a user