mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Blimp: add RebootRequred to stream rate parameters
This commit is contained in:
parent
c33590a63b
commit
5ae96b4656
@ -217,6 +217,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 0),
|
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 0),
|
||||||
|
|
||||||
@ -226,6 +227,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 0),
|
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 0),
|
||||||
|
|
||||||
@ -235,6 +237,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 0),
|
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 0),
|
||||||
|
|
||||||
@ -244,6 +247,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 0),
|
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 0),
|
||||||
|
|
||||||
@ -253,6 +257,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 0),
|
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 0),
|
||||||
|
|
||||||
@ -262,6 +267,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 0),
|
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 0),
|
||||||
|
|
||||||
@ -271,6 +277,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 0),
|
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 0),
|
||||||
|
|
||||||
@ -280,6 +287,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 0),
|
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 0),
|
||||||
|
|
||||||
@ -289,6 +297,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 0),
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
Loading…
Reference in New Issue
Block a user