mirror of https://github.com/ArduPilot/ardupilot
expose mavlink stream rates as parameters
This commit is contained in:
parent
c4b7a3116a
commit
922139b824
|
@ -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,
|
||||
|
|
|
@ -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…
Reference in New Issue