diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 12b00cb5c8f37..ebb4dd3b3ba40 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -17,6 +17,7 @@ const AP_Param::Info Tracker::var_info[] = { // @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network // @Range: 1 255 // @User: Advanced + // @RebootRequired: True GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID), // @Param: SYSID_MYGCS diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index f8f1376c90a2a..07be05012e230 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -42,6 +42,7 @@ const AP_Param::Info Copter::var_info[] = { // @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network // @Range: 1 255 // @User: Advanced + // @RebootRequired: True GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID), // @Param: SYSID_MYGCS diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 166b141c87bf8..5fa0b447ceeef 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -27,6 +27,7 @@ const AP_Param::Info Plane::var_info[] = { // @Range: 1 255 // @Increment: 1 // @User: Advanced + // @RebootRequired: True GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), // AP_SerialManager was here diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 2be5f65171e20..157d879c40b3b 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -44,6 +44,7 @@ const AP_Param::Info Sub::var_info[] = { // @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network // @Range: 1 255 // @User: Advanced + // @RebootRequired: True GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID), // @Param: SYSID_MYGCS diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index 70d5e76e7eb91..89dd040e006e9 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -35,6 +35,7 @@ const AP_Param::Info Blimp::var_info[] = { // @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network // @Range: 1 255 // @User: Advanced + // @RebootRequired: True GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID), // @Param: SYSID_MYGCS diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index f997e15797720..55bd46420e1b2 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -38,6 +38,7 @@ const AP_Param::Info Rover::var_info[] = { // @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network // @Range: 1 255 // @User: Advanced + // @RebootRequired: True GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID), // @Param: SYSID_MYGCS diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 3b00ce8bafc85..cebb653b2e4b3 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -464,6 +464,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network // @Range: 1 255 // @User: Advanced + // @RebootRequired: True GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID), #endif