Skip to content

Commit

Permalink
Merge pull request mavlink#531 from Dronecode/fix-race-in-camera
Browse files Browse the repository at this point in the history
Fix race in camera backend
  • Loading branch information
julianoes authored Sep 4, 2018
2 parents 14ec092 + 8b39dd6 commit e5cac2a
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 9 deletions.
2 changes: 1 addition & 1 deletion backend/cmake/MacOSXFrameworkInfo.plist.in
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<key>CFBundleVersion</key>
<string>1</string>
<key>CFBundleShortVersionString</key>
<string>0.2.2</string>
<string>0.2.3</string>
<key>MinimumOSVersion</key>
<string>11.3</string>
<key>CSResourcesFileMapped</key>
Expand Down
19 changes: 12 additions & 7 deletions backend/src/plugins/camera/camera_service_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -171,11 +171,12 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service {

bool is_finished = false;

_camera.subscribe_mode([&writer, &stream_closed_promise, &is_finished](
_camera.subscribe_mode([this, &writer, &stream_closed_promise, &is_finished](
const dronecode_sdk::Camera::Mode mode) {
rpc::camera::ModeResponse rpc_mode_response;
rpc_mode_response.set_camera_mode(translateCameraMode(mode));

std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_mode_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
Expand Down Expand Up @@ -296,13 +297,14 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service {
bool is_finished = false;

_camera.subscribe_video_stream_info(
[&writer, &stream_closed_promise, &is_finished](
[this, &writer, &stream_closed_promise, &is_finished](
const dronecode_sdk::Camera::VideoStreamInfo video_info) {
rpc::camera::VideoStreamInfoResponse rpc_video_stream_info_response;
auto video_stream_info = translateVideoStreamInfo(video_info);
rpc_video_stream_info_response.set_allocated_video_stream_info(
video_stream_info.release());

std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_video_stream_info_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
Expand All @@ -324,12 +326,13 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service {

bool is_finished = false;

_camera.subscribe_capture_info([&writer, &stream_closed_promise, &is_finished](
_camera.subscribe_capture_info([this, &writer, &stream_closed_promise, &is_finished](
const dronecode_sdk::Camera::CaptureInfo capture_info) {
rpc::camera::CaptureInfoResponse rpc_capture_info_response;
auto rpc_capture_info = translateCaptureInfo(capture_info);
rpc_capture_info_response.set_allocated_capture_info(rpc_capture_info.release());

std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_capture_info_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
Expand Down Expand Up @@ -465,7 +468,7 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service {
auto rpc_camera_status = translateCameraStatus(camera_status);
rpc_camera_status_response.set_allocated_camera_status(rpc_camera_status.release());

std::lock_guard<std::mutex> lock(_subscribe_camera_status_mutex);
std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_camera_status_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
Expand Down Expand Up @@ -548,7 +551,7 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service {
bool is_finished = false;

_camera.subscribe_current_settings(
[&writer, &stream_closed_promise, &is_finished](
[this, &writer, &stream_closed_promise, &is_finished](
const std::vector<dronecode_sdk::Camera::Setting> current_settings) {
rpc::camera::CurrentSettingsResponse rpc_current_setting_response;

Expand All @@ -557,6 +560,7 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service {
translateSetting(current_setting, rpc_current_setting);
}

std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_current_setting_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
Expand Down Expand Up @@ -617,7 +621,7 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service {
bool is_finished = false;

_camera.subscribe_possible_setting_options(
[&writer, &stream_closed_promise, &is_finished](
[this, &writer, &stream_closed_promise, &is_finished](
const std::vector<dronecode_sdk::Camera::SettingOptions> setting_options) {
rpc::camera::PossibleSettingOptionsResponse rpc_setting_options_response;

Expand All @@ -626,6 +630,7 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service {
translateSettingOptions(setting_option, rpc_setting_option);
}

std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_setting_options_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
Expand Down Expand Up @@ -705,7 +710,7 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service {

private:
Camera &_camera;
std::mutex _subscribe_camera_status_mutex{};
std::mutex _subscribe_mutex{};
};

} // namespace backend
Expand Down
2 changes: 1 addition & 1 deletion backend/tools/push_backend_framework_to_s3.bash
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ set -e

SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
FAT_BIN_DIR=${SCRIPT_DIR}/../../build/fat_bin
CURRENT_VERSION=0.2.2
CURRENT_VERSION=0.2.3

aws s3 cp ${FAT_BIN_DIR}/dronecode-backend.zip s3://dronecode-sdk/dronecode-backend-latest.zip
aws s3api put-object-acl --bucket dronecode-sdk --key dronecode-backend-latest.zip --acl public-read
Expand Down

0 comments on commit e5cac2a

Please sign in to comment.