Skip to content

Commit

Permalink
Merge pull request #521 from Dronecode/add-set-rtl-after-mission
Browse files Browse the repository at this point in the history
Add get/set rtl after mission
  • Loading branch information
julianoes committed Aug 31, 2018
2 parents a31e06b + f2dba1d commit 89ee890
Show file tree
Hide file tree
Showing 3 changed files with 111 additions and 33 deletions.
90 changes: 57 additions & 33 deletions backend/src/plugins/mission/mission_service_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -158,6 +158,63 @@ class MissionServiceImpl final : public dronecode_sdk::rpc::mission::MissionServ
return grpc::Status::OK;
}

grpc::Status SubscribeMissionProgress(
grpc::ServerContext * /* context */,
const dronecode_sdk::rpc::mission::SubscribeMissionProgressRequest * /* request */,
grpc::ServerWriter<rpc::mission::MissionProgressResponse> *writer) override
{
std::promise<void> stream_closed_promise;
auto stream_closed_future = stream_closed_promise.get_future();

bool is_finished = false;

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

auto rpc_mission_progress =
std::unique_ptr<dronecode_sdk::rpc::mission::MissionProgress>(
new dronecode_sdk::rpc::mission::MissionProgress);
rpc_mission_progress->set_current_item_index(current);
rpc_mission_progress->set_mission_count(total);

rpc_mission_progress_response.set_allocated_mission_progress(
rpc_mission_progress.release());

if (!writer->Write(rpc_mission_progress_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
}
});

stream_closed_future.wait();
return grpc::Status::OK;
}

grpc::Status GetReturnToLaunchAfterMission(
grpc::ServerContext * /* context */,
const rpc::mission::GetReturnToLaunchAfterMissionRequest * /* request */,
rpc::mission::GetReturnToLaunchAfterMissionResponse *response) override
{
if (response != nullptr) {
response->set_enable(_mission.get_return_to_launch_after_mission());
}

return grpc::Status::OK;
}

grpc::Status SetReturnToLaunchAfterMission(
grpc::ServerContext * /* context */,
const rpc::mission::SetReturnToLaunchAfterMissionRequest *request,
rpc::mission::SetReturnToLaunchAfterMissionResponse * /* response */) override
{
if (request != nullptr) {
_mission.set_return_to_launch_after_mission(request->enable());
}

return grpc::Status::OK;
}

static void translateMissionItem(const std::shared_ptr<MissionItem> mission_item,
rpc::mission::MissionItem *rpc_mission_item)
{
Expand Down Expand Up @@ -275,39 +332,6 @@ class MissionServiceImpl final : public dronecode_sdk::rpc::mission::MissionServ
return rpc_mission_result;
}

grpc::Status SubscribeMissionProgress(
grpc::ServerContext * /* context */,
const dronecode_sdk::rpc::mission::SubscribeMissionProgressRequest * /* request */,
grpc::ServerWriter<rpc::mission::MissionProgressResponse> *writer) override
{
std::promise<void> stream_closed_promise;
auto stream_closed_future = stream_closed_promise.get_future();

bool is_finished = false;

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

auto rpc_mission_progress =
std::unique_ptr<dronecode_sdk::rpc::mission::MissionProgress>(
new dronecode_sdk::rpc::mission::MissionProgress);
rpc_mission_progress->set_current_item_index(current);
rpc_mission_progress->set_mission_count(total);

rpc_mission_progress_response.set_allocated_mission_progress(
rpc_mission_progress.release());

if (!writer->Write(rpc_mission_progress_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
}
});

stream_closed_future.wait();
return grpc::Status::OK;
}

Mission &_mission;
};

Expand Down
52 changes: 52 additions & 0 deletions backend/test/mission_service_impl_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -653,6 +653,58 @@ TEST_F(MissionServiceImplProgressTest, SendsMultipleMissionProgressEvents)
EXPECT_EQ(expected_progress_events, received_progress_events);
}

class MissionServiceImplGetRTLAfterMissionTest : public MissionServiceImplTestBase {
protected:
void checkGetRTLAfterMissionReturns(const bool expected_value);
};

TEST_F(MissionServiceImplGetRTLAfterMissionTest, getRTLAfterMissionDoesNotCrashWithNullResponse)
{
_mission_service.GetReturnToLaunchAfterMission(nullptr, nullptr, nullptr);
}

TEST_F(MissionServiceImplGetRTLAfterMissionTest, getRTLAfterMissionReturnsCorrectValue)
{
checkGetRTLAfterMissionReturns(true);
checkGetRTLAfterMissionReturns(false);
}

void MissionServiceImplGetRTLAfterMissionTest::checkGetRTLAfterMissionReturns(
const bool expected_value)
{
dronecode_sdk::rpc::mission::GetReturnToLaunchAfterMissionResponse response;
ON_CALL(_mission, get_return_to_launch_after_mission()).WillByDefault(Return(expected_value));

_mission_service.GetReturnToLaunchAfterMission(nullptr, nullptr, &response);
EXPECT_EQ(expected_value, response.enable());
}

class MissionServiceImplSetRTLAfterMissionTest : public MissionServiceImplTestBase {
protected:
void checkSetRTLAfterMissionSets(const bool expected_value);
};

TEST_F(MissionServiceImplSetRTLAfterMissionTest, setRTLAfterMissionDoesNotCrashWithNullRequest)
{
_mission_service.SetReturnToLaunchAfterMission(nullptr, nullptr, nullptr);
}

TEST_F(MissionServiceImplSetRTLAfterMissionTest, setRTLAfterMissionSetsRightValue)
{
checkSetRTLAfterMissionSets(false);
checkSetRTLAfterMissionSets(true);
}

void MissionServiceImplSetRTLAfterMissionTest::checkSetRTLAfterMissionSets(
const bool expected_value)
{
EXPECT_CALL(_mission, set_return_to_launch_after_mission(expected_value));
dronecode_sdk::rpc::mission::SetReturnToLaunchAfterMissionRequest request;
request.set_enable(expected_value);

_mission_service.SetReturnToLaunchAfterMission(nullptr, &request, nullptr);
}

std::vector<InputPair> generateInputPairs()
{
std::vector<InputPair> input_pairs;
Expand Down
2 changes: 2 additions & 0 deletions plugins/mission/mocks/mission_mock.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ class MockMission {
MOCK_CONST_METHOD0(total_mission_items, int());
MOCK_CONST_METHOD0(mission_finished, bool());
MOCK_CONST_METHOD1(subscribe_progress, void(Mission::progress_callback_t));
MOCK_CONST_METHOD0(get_return_to_launch_after_mission, bool());
MOCK_CONST_METHOD1(set_return_to_launch_after_mission, void(bool));
};

} // namespace testing
Expand Down

0 comments on commit 89ee890

Please sign in to comment.