forked from Archive/PX4-Autopilot
MAVLink app: Do not warn about required reboot but rely on param meta. Fixes #7642
This commit is contained in:
parent
0668d61665
commit
6e97aec8ce
|
@ -611,17 +611,6 @@ void Mavlink::mavlink_update_system()
|
|||
_param_initialized = true;
|
||||
}
|
||||
|
||||
/* warn users that they need to reboot to take this
|
||||
* into effect
|
||||
*/
|
||||
if (system_id != mavlink_system.sysid) {
|
||||
send_statustext_critical("Save params and reboot to change SYSID");
|
||||
}
|
||||
|
||||
if (component_id != mavlink_system.compid) {
|
||||
send_statustext_critical("Save params and reboot to change COMPID");
|
||||
}
|
||||
|
||||
int32_t system_type;
|
||||
param_get(_param_system_type, &system_type);
|
||||
|
||||
|
|
|
@ -36,6 +36,7 @@
|
|||
* @group MAVLink
|
||||
* @min 1
|
||||
* @max 250
|
||||
* @reboot_required true
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MAV_SYS_ID, 1);
|
||||
|
||||
|
@ -44,6 +45,7 @@ PARAM_DEFINE_INT32(MAV_SYS_ID, 1);
|
|||
* @group MAVLink
|
||||
* @min 1
|
||||
* @max 250
|
||||
* @reboot_required true
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MAV_COMP_ID, 1);
|
||||
|
||||
|
|
Loading…
Reference in New Issue