Skip to content

Commit

Permalink
params: fix double promise call
Browse files Browse the repository at this point in the history
This fixes a segfault/abort when using get_all_params(). The issue was
that the timeout handler was not removed as it should have been, and so
after a successful completion, we got another call from the timeout
handler which then satisfies the promise a second time which is not
possible.

This did not show up in the integration test (or at least not often)
because the test was already destructed by the time the timeout would
trigger.
  • Loading branch information
julianoes committed May 23, 2022
1 parent 14918d7 commit bc73a2b
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 0 deletions.
2 changes: 2 additions & 0 deletions src/integration_tests/param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,8 @@ TEST_F(SitlTest, GetAllParams)
for (const auto& mixed_param : all_mixed) {
std::cout << mixed_param.first << " : " << mixed_param.second << '\n';
}

std::this_thread::sleep_for(std::chrono::seconds(2));
}

TEST_F(SitlTest, APParam)
Expand Down
1 change: 1 addition & 0 deletions src/mavsdk/core/mavlink_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -913,6 +913,7 @@ void MAVLinkParameters::process_param_value(const mavlink_message_t& message)
// check if we are looking for param list
if (_all_params_callback) {
if (param_value.param_index + 1 == param_value.param_count) {
_parent.unregister_timeout_handler(_all_params_timeout_cookie);
lock.unlock();
_all_params_callback(_all_params);
} else {
Expand Down

0 comments on commit bc73a2b

Please sign in to comment.