Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

core: fix get_all_params caching #2457

Merged
merged 1 commit into from
Dec 3, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions src/mavsdk/core/mavlink_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -458,6 +458,8 @@ void MavlinkParameterClient::do_work()
_timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
},
[&](WorkItemGet& item) {
// We can't rely on the cache as we haven't implemented the hash check.
clear_cache();
if (!send_get_param_message(item)) {
LogErr() << "Send message failed";
work_queue_guard->pop_front();
Expand All @@ -474,6 +476,8 @@ void MavlinkParameterClient::do_work()
_timeout_handler.add([this] { receive_timeout(); }, _timeout_s_callback());
},
[&](WorkItemGetAll& item) {
// We can't rely on the cache as we haven't implemented the hash check.
clear_cache();
if (!send_request_list_message()) {
LogErr() << "Send message failed";
work_queue_guard->pop_front();
Expand Down