diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index be8d07a7a6..870e27766d 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -751,14 +751,85 @@ void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char default stream rates to 1Hz */ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = { + // @Param: RAW_SENS + // @DisplayName: Raw sensor stream rate + // @Description: Raw sensor stream rate to ground station + // @Units: Hz + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRates[0], 1), + + // @Param: EXT_STAT + // @DisplayName: Extended status stream rate to ground station + // @Description: Extended status stream rate to ground station + // @Units: Hz + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRates[1], 1), + + // @Param: RC_CHAN + // @DisplayName: RC Channel stream rate to ground station + // @Description: RC Channel stream rate to ground station + // @Units: Hz + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK, streamRates[2], 1), + + // @Param: RAW_CTRL + // @DisplayName: Raw Control stream rate to ground station + // @Description: Raw Control stream rate to ground station + // @Units: Hz + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK, streamRates[3], 1), + + // @Param: POSITION + // @DisplayName: Position stream rate to ground station + // @Description: Position stream rate to ground station + // @Units: Hz + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK, streamRates[4], 1), + + // @Param: EXTRA1 + // @DisplayName: Extra data type 1 stream rate to ground station + // @Description: Extra data type 1 stream rate to ground station + // @Units: Hz + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK, streamRates[5], 1), + + // @Param: EXTRA2 + // @DisplayName: Extra data type 2 stream rate to ground station + // @Description: Extra data type 2 stream rate to ground station + // @Units: Hz + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK, streamRates[6], 1), + + // @Param: EXTRA3 + // @DisplayName: Extra data type 3 stream rate to ground station + // @Description: Extra data type 3 stream rate to ground station + // @Units: Hz + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK, streamRates[7], 1), + + // @Param: PARAMS + // @DisplayName: Parameter stream rate to ground station + // @Description: Parameter stream rate to ground station + // @Units: Hz + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 50), AP_GROUPEND };