Skip to content

Commit

Permalink
Merge pull request #901 from mavlink/fix-camera-settings-deadlock
Browse files Browse the repository at this point in the history
Fix camera settings deadlocks
  • Loading branch information
julianoes committed Nov 13, 2019
2 parents 7cacb3a + ff70873 commit 480a93c
Showing 1 changed file with 63 additions and 23 deletions.
86 changes: 63 additions & 23 deletions src/plugins/camera/camera_impl.cpp
Expand Up @@ -391,11 +391,9 @@ void CameraImpl::start_photo_interval_async(
float interval_s, const Camera::result_callback_t& callback)
{
if (!interval_valid(interval_s)) {
if (callback) {
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::WRONG_ARGUMENT); });
}
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::WRONG_ARGUMENT); });
return;
}

Expand Down Expand Up @@ -1096,7 +1094,9 @@ void CameraImpl::receive_set_mode_command_result(
Camera::Result camera_result = camera_result_from_command_result(command_result);

if (callback) {
callback(camera_result, mode);
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback, camera_result, mode]() { temp_callback(camera_result, mode); });
}

if (command_result == MAVLinkCommands::Result::SUCCESS && _camera_definition) {
Expand Down Expand Up @@ -1237,7 +1237,9 @@ void CameraImpl::set_option_async(
if (!_camera_definition) {
LogWarn() << "Error: no camera defnition available yet.";
if (callback) {
callback(Camera::Result::ERROR);
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::ERROR); });
}
return;
}
Expand All @@ -1251,15 +1253,19 @@ void CameraImpl::set_option_async(
if (!_camera_definition->get_all_options(setting_id, all_values)) {
if (callback) {
LogErr() << "Could not get all options to get type for range param.";
callback(Camera::Result::ERROR);
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::ERROR); });
}
return;
}

if (all_values.size() == 0) {
if (callback) {
LogErr() << "Could not get any options to get type for range param.";
callback(Camera::Result::ERROR);
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::ERROR); });
}
return;
}
Expand All @@ -1269,7 +1275,9 @@ void CameraImpl::set_option_async(
if (!value.set_as_same_type(option.option_id)) {
if (callback) {
LogErr() << "Could not set option value to given type.";
callback(Camera::Result::ERROR);
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::ERROR); });
}
return;
}
Expand All @@ -1278,7 +1286,9 @@ void CameraImpl::set_option_async(
if (!_camera_definition->get_option_value(setting_id, option.option_id, value)) {
if (callback) {
LogErr() << "Could not get option value.";
callback(Camera::Result::ERROR);
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::ERROR); });
}
return;
}
Expand All @@ -1294,7 +1304,9 @@ void CameraImpl::set_option_async(
if (!allowed) {
LogErr() << "Setting " << setting_id << "(" << option.option_id << ") not allowed";
if (callback) {
callback(Camera::Result::ERROR);
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::ERROR); });
}
return;
}
Expand All @@ -1305,17 +1317,34 @@ void CameraImpl::set_option_async(
value,
[this, callback, setting_id, value](MAVLinkParameters::Result result) {
if (result == MAVLinkParameters::Result::SUCCESS) {
if (this->_camera_definition) {
_camera_definition->set_setting(setting_id, value);
refresh_params();
if (!this->_camera_definition) {
if (callback) {
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::ERROR); });
}
return;
}
if (callback) {
callback(Camera::Result::SUCCESS);

if (!_camera_definition->set_setting(setting_id, value)) {
if (callback) {
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::ERROR); });
}
return;
}
} else {

if (callback) {
callback(Camera::Result::ERROR);
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback]() { temp_callback(Camera::Result::SUCCESS); });
}

// FIXME: We are already holding the lock when this lambda is run and need to
// schedule the refresh_params() for later.
// We (ab)use the thread pool for the user callbacks for this.
_parent->call_user_callback([this]() { refresh_params(); });
}
},
this,
Expand Down Expand Up @@ -1351,7 +1380,10 @@ void CameraImpl::get_option_async(
LogWarn() << "Error: no camera defnition available yet.";
if (callback) {
Camera::Option empty_option{};
callback(Camera::Result::ERROR, empty_option);
const auto temp_callback = callback;
_parent->call_user_callback([temp_callback, empty_option]() {
temp_callback(Camera::Result::ERROR, empty_option);
});
}
return;
}
Expand All @@ -1365,14 +1397,19 @@ void CameraImpl::get_option_async(
if (!is_setting_range(setting_id)) {
get_option_str(setting_id, new_option.option_id, new_option.option_description);
}
callback(Camera::Result::SUCCESS, new_option);
const auto temp_callback = callback;
_parent->call_user_callback([temp_callback, new_option]() {
temp_callback(Camera::Result::SUCCESS, new_option);
});
}
} else {
// If this still happens, we request the param, but also complain.
LogWarn() << "Setting '" << setting_id << "' not found.";
if (callback) {
Camera::Option no_option{};
callback(Camera::Result::ERROR, no_option);
const auto temp_callback = callback;
_parent->call_user_callback(
[temp_callback, no_option]() { temp_callback(Camera::Result::ERROR, no_option); });
}
}
}
Expand Down Expand Up @@ -1519,7 +1556,10 @@ void CameraImpl::refresh_params()
if (!this->_camera_definition) {
return;
}
this->_camera_definition->set_setting(param_name, value);

if (!this->_camera_definition->set_setting(param_name, value)) {
return;
}

if (is_last) {
notify_current_settings();
Expand Down

0 comments on commit 480a93c

Please sign in to comment.