From 922139b824a14aa7075816f1152ea0f4cb837f4a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 12 Feb 2012 21:08:37 +1100 Subject: [PATCH] expose mavlink stream rates as parameters --- ArduPlane/Parameters.h | 4 ++-- ArduPlane/Parameters.pde | 4 +++- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 441ef0049f..6e5d3e904d 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -53,8 +53,8 @@ public: // 110: Telemetry control // - k_param_streamrates_port0 = 110, - k_param_streamrates_port3, + k_param_gcs0 = 110, // stream rates for port0 + k_param_gcs3, // stream rates for port3 k_param_sysid_this_mav, k_param_sysid_my_gcs, k_param_serial3_baud, diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index e7f9d77805..117a734511 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -121,7 +121,9 @@ static const AP_Param::Info var_info[] PROGMEM = { GGROUP(pidNavPitchAltitude, "ALT2PTCH_", PID), // variables not in the g class which contain EEPROM saved variables - GOBJECT(compass, "COMPASS_", Compass) + GOBJECT(compass, "COMPASS_", Compass), + GOBJECT(gcs0, "SR0_", GCS_MAVLINK), + GOBJECT(gcs3, "SR3_", GCS_MAVLINK) };