ArduCopter: add RebootRequred to stream rate parameters
This commit is contained in:
parent
75045057b7
commit
c80cd1daa5
@ -380,6 +380,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @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),
|
||||||
|
|
||||||
@ -389,6 +390,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @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),
|
||||||
|
|
||||||
@ -398,6 +400,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @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),
|
||||||
|
|
||||||
@ -407,6 +410,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @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),
|
||||||
|
|
||||||
@ -416,6 +420,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @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),
|
||||||
|
|
||||||
@ -425,6 +430,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @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),
|
||||||
|
|
||||||
@ -434,6 +440,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @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),
|
||||||
|
|
||||||
@ -443,6 +450,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @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),
|
||||||
|
|
||||||
@ -452,6 +460,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @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),
|
||||||
|
|
||||||
@ -461,6 +470,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 50
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 0),
|
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
Loading…
Reference in New Issue
Block a user