mirror of https://github.com/ArduPilot/ardupilot
Rover: change SRx_ docs value 1 50
This commit is contained in:
parent
5b684e5e2b
commit
0a9f319c85
|
@ -363,7 +363,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
// @DisplayName: Raw sensor stream rate
|
||||
// @Description: Raw sensor stream rate to ground station
|
||||
// @Units: Hz
|
||||
// @Range: 0 10
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1),
|
||||
|
@ -372,7 +372,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
// @DisplayName: Extended status stream rate to ground station
|
||||
// @Description: Extended status stream rate to ground station
|
||||
// @Units: Hz
|
||||
// @Range: 0 10
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1),
|
||||
|
@ -381,7 +381,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
// @DisplayName: RC Channel stream rate to ground station
|
||||
// @Description: RC Channel stream rate to ground station
|
||||
// @Units: Hz
|
||||
// @Range: 0 10
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1),
|
||||
|
@ -390,7 +390,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
// @DisplayName: Raw Control stream rate to ground station
|
||||
// @Description: Raw Control stream rate to ground station
|
||||
// @Units: Hz
|
||||
// @Range: 0 10
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1),
|
||||
|
@ -399,7 +399,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
// @DisplayName: Position stream rate to ground station
|
||||
// @Description: Position stream rate to ground station
|
||||
// @Units: Hz
|
||||
// @Range: 0 10
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1),
|
||||
|
@ -408,7 +408,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
// @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
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1),
|
||||
|
@ -417,7 +417,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
// @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
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1),
|
||||
|
@ -426,7 +426,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
// @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
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1),
|
||||
|
@ -435,7 +435,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||
// @DisplayName: Parameter stream rate to ground station
|
||||
// @Description: Parameter stream rate to ground station
|
||||
// @Units: Hz
|
||||
// @Range: 0 10
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10),
|
||||
|
|
Loading…
Reference in New Issue