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

backend: fix crash in mission #581

Merged
merged 1 commit into from
Oct 26, 2018
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
9 changes: 5 additions & 4 deletions backend/src/plugins/mission/mission_service_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -173,10 +173,10 @@ class MissionServiceImpl final : public dronecode_sdk::rpc::mission::MissionServ
std::promise<void> stream_closed_promise;
auto stream_closed_future = stream_closed_promise.get_future();

bool is_finished = false;
auto is_finished = std::make_shared<bool>(false);

_mission.subscribe_progress(
[&writer, &stream_closed_promise, &is_finished](int current, int total) {
[this, &writer, &stream_closed_promise, is_finished](int current, int total) {
dronecode_sdk::rpc::mission::MissionProgressResponse rpc_mission_progress_response;

auto rpc_mission_progress =
Expand All @@ -188,8 +188,9 @@ class MissionServiceImpl final : public dronecode_sdk::rpc::mission::MissionServ
rpc_mission_progress_response.set_allocated_mission_progress(
rpc_mission_progress.release());

if (!writer->Write(rpc_mission_progress_response) && !is_finished) {
is_finished = true;
if (!*is_finished && !writer->Write(rpc_mission_progress_response)) {
_mission.subscribe_progress(nullptr);
*is_finished = true;
stream_closed_promise.set_value();
}
});
Expand Down