Plane: add support for 4th mavlink channel

This commit is contained in:
Randy Mackay 2015-05-15 13:24:39 +09:00
parent d8b7e4a199
commit 174c55b0af
3 changed files with 12 additions and 0 deletions

View File

@ -137,6 +137,7 @@ public:
k_param_land_disarm_delay,
k_param_glide_slope_threshold,
k_param_rudder_only,
k_param_gcs3, // 93
// 100: Arming parameters
k_param_arming = 100,

View File

@ -1110,6 +1110,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),

View File

@ -135,6 +135,11 @@ static void init_ardupilot()
gcs[2].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 1);
#endif
#if MAVLINK_COMM_NUM_BUFFERS > 3
// setup serial port for fourth telemetry port (not used by default)
gcs[3].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 2);
#endif
// setup frsky
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.init(serial_manager);