Skip to content

Commit

Permalink
core: keep lock while calling callback
Browse files Browse the repository at this point in the history
I had introduced unlock calls before calling callbacks in order to
prevent deadlocks. I don't think this is required anymore, as all
callbacks back to the user are now served later from a queue. This does
assume that we don't have any such deadlocks internally though.
  • Loading branch information
julianoes committed May 25, 2022
1 parent bc73a2b commit 5fbd395
Showing 1 changed file with 4 additions and 8 deletions.
12 changes: 4 additions & 8 deletions src/mavsdk/core/mavlink_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -560,7 +560,7 @@ MAVLinkParameters::get_param_custom(const std::string& name)

void MAVLinkParameters::get_all_params_async(const GetAllParamsCallback& callback)
{
std::unique_lock<std::mutex> lock(_all_params_mutex);
std::lock_guard<std::mutex> lock(_all_params_mutex);

_all_params_callback = callback;

Expand All @@ -575,7 +575,6 @@ void MAVLinkParameters::get_all_params_async(const GetAllParamsCallback& callbac

if (!_parent.send_message(msg)) {
LogErr() << "Failed to send param list request!";
lock.unlock();
callback(std::map<std::string, ParamValue>{});
}

Expand Down Expand Up @@ -697,11 +696,10 @@ void MAVLinkParameters::do_work()
switch (work->type) {
case WorkItem::Type::Set: {
if (!work->exact_type_known) {
std::unique_lock<std::mutex> lock(_all_params_mutex);
std::lock_guard<std::mutex> lock(_all_params_mutex);
const auto it = _all_params.find(work->param_name);
if (it == _all_params.end()) {
LogErr() << "Don't know the type of param_set";
lock.unlock();
if (std::get_if<SetParamCallback>(&work->callback)) {
const auto& callback = std::get<SetParamCallback>(work->callback);
if (callback) {
Expand Down Expand Up @@ -907,14 +905,13 @@ void MAVLinkParameters::process_param_value(const mavlink_message_t& message)
std::string param_id = extract_safe_param_id(param_value.param_id);

{
std::unique_lock<std::mutex> lock(_all_params_mutex);
std::lock_guard<std::mutex> lock(_all_params_mutex);
_all_params[param_id] = received_value;

// 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 {
_parent.unregister_timeout_handler(_all_params_timeout_cookie);
Expand Down Expand Up @@ -1265,10 +1262,9 @@ void MAVLinkParameters::process_param_ext_set(const mavlink_message_t& message)
void MAVLinkParameters::receive_timeout()
{
{
std::unique_lock<std::mutex> lock(_all_params_mutex);
std::lock_guard<std::mutex> lock(_all_params_mutex);
// first check if we are waiting for param list response
if (_all_params_callback) {
lock.unlock();
_all_params_callback({});
return;
}
Expand Down

0 comments on commit 5fbd395

Please sign in to comment.