Browse Source

expose mavlink stream rates as parameters

mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
676ca03977
  1. 4
      ArduPlane/Parameters.h
  2. 4
      ArduPlane/Parameters.pde

4
ArduPlane/Parameters.h

@ -53,8 +53,8 @@ public: @@ -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,

4
ArduPlane/Parameters.pde

@ -121,7 +121,9 @@ static const AP_Param::Info var_info[] PROGMEM = { @@ -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)
};

Loading…
Cancel
Save