ArduPlane: invalidate param count when changing param tree structure

This commit is contained in:
Andrew Tridgell 2020-04-19 09:01:25 +10:00
parent 265b9a42fb
commit d0a509eef1
1 changed files with 3 additions and 0 deletions

View File

@ -754,6 +754,9 @@ bool QuadPlane::setup(void)
AP_Param::convert_old_parameters(&q_conversion_table[0], ARRAY_SIZE(q_conversion_table));
// param count will have changed
AP_Param::invalidate_count();
gcs().send_text(MAV_SEVERITY_INFO, "QuadPlane initialised");
initialised = true;
return true;