mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 01:48:29 -04:00
AP_Param: Fix failing to invalidate the cached parameter count
This would cause a GCS to download fewer then the requested number of parameters
This commit is contained in:
parent
9f32170da7
commit
55c00b9957
@ -444,6 +444,7 @@ public:
|
|||||||
|
|
||||||
// set frame type flags. Used to unhide frame specific parameters
|
// set frame type flags. Used to unhide frame specific parameters
|
||||||
static void set_frame_type_flags(uint16_t flags_to_set) {
|
static void set_frame_type_flags(uint16_t flags_to_set) {
|
||||||
|
_parameter_count = 0;
|
||||||
_frame_type_flags |= flags_to_set;
|
_frame_type_flags |= flags_to_set;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user