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

Add get/set rtl altitude #519

Merged
merged 2 commits into from
Aug 30, 2018
Merged
Show file tree
Hide file tree
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
43 changes: 43 additions & 0 deletions backend/src/plugins/action/action_service_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -198,6 +198,49 @@ class ActionServiceImpl final : public rpc::action::ActionService::Service {
return grpc::Status::OK;
}

grpc::Status
GetReturnToLaunchAltitude(grpc::ServerContext * /* context */,
const rpc::action::GetReturnToLaunchAltitudeRequest * /* request */,
rpc::action::GetReturnToLaunchAltitudeResponse *response) override
{
if (response != nullptr) {
auto result_pair = _action.get_return_to_launch_return_altitude();

auto *rpc_action_result = new rpc::action::ActionResult();
rpc_action_result->set_result(
static_cast<rpc::action::ActionResult::Result>(result_pair.first));
rpc_action_result->set_result_str(action_result_str(result_pair.first));

response->set_allocated_action_result(rpc_action_result);
response->set_relative_altitude_m(result_pair.second);
}

return grpc::Status::OK;
}

grpc::Status
SetReturnToLaunchAltitude(grpc::ServerContext * /* context */,
const rpc::action::SetReturnToLaunchAltitudeRequest *request,
rpc::action::SetReturnToLaunchAltitudeResponse *response) override
{
if (request != nullptr) {
const auto requested_altitude = request->relative_altitude_m();
const auto action_result =
_action.set_return_to_launch_return_altitude(requested_altitude);

if (response != nullptr) {
auto *rpc_action_result = new rpc::action::ActionResult();
rpc_action_result->set_result(
static_cast<rpc::action::ActionResult::Result>(action_result));
rpc_action_result->set_result_str(action_result_str(action_result));

response->set_allocated_action_result(rpc_action_result);
}
}

return grpc::Status::OK;
}

private:
Action &_action;
};
Expand Down
107 changes: 107 additions & 0 deletions backend/test/action_service_impl_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,10 @@ std::string
transitionToFWAndGetTranslatedResult(const dronecode_sdk::ActionResult transition_to_fw_result);
std::string
transitionToMCAndGetTranslatedResult(const dronecode_sdk::ActionResult transition_to_fw_result);
std::string
getReturnToLaunchAltitudeAndGetTranslatedResult(const dronecode_sdk::ActionResult action_result);
std::string
setReturnToLaunchAltitudeAndGetTranslatedResult(const dronecode_sdk::ActionResult action_result);

class ActionServiceImplTest : public ::testing::TestWithParam<InputPair> {};

Expand Down Expand Up @@ -388,6 +392,109 @@ TEST_F(ActionServiceImplTest, setMaxSpeedSetsRightValue)
actionService.SetMaximumSpeed(nullptr, &request, nullptr);
}

TEST_P(ActionServiceImplTest, getReturnToLaunchAltitudeResultIsTranslatedCorrectly)
{
const auto rpc_result = getReturnToLaunchAltitudeAndGetTranslatedResult(GetParam().second);
EXPECT_EQ(rpc_result, GetParam().first);
}

std::string
getReturnToLaunchAltitudeAndGetTranslatedResult(const dronecode_sdk::ActionResult action_result)
{
MockAction action;
const auto return_pair = std::make_pair<>(action_result, ARBITRARY_ALTITUDE);
ON_CALL(action, get_return_to_launch_return_altitude()).WillByDefault(Return(return_pair));
ActionServiceImpl actionService(action);
dronecode_sdk::rpc::action::GetReturnToLaunchAltitudeResponse response;

actionService.GetReturnToLaunchAltitude(nullptr, nullptr, &response);

return ActionResult::Result_Name(response.action_result().result());
}

TEST_F(ActionServiceImplTest, getReturnToLaunchAltitudeCallsGetter)
{
MockAction action;
ActionServiceImpl actionService(action);
EXPECT_CALL(action, get_return_to_launch_return_altitude()).Times(1);
dronecode_sdk::rpc::action::GetReturnToLaunchAltitudeResponse response;

actionService.GetReturnToLaunchAltitude(nullptr, nullptr, &response);
}

TEST_P(ActionServiceImplTest, getsCorrectReturnToLaunchAltitude)
{
MockAction action;
ActionServiceImpl actionService(action);
const auto expected_pair = std::make_pair<>(GetParam().second, ARBITRARY_ALTITUDE);
ON_CALL(action, get_return_to_launch_return_altitude()).WillByDefault(Return(expected_pair));
dronecode_sdk::rpc::action::GetReturnToLaunchAltitudeResponse response;

actionService.GetReturnToLaunchAltitude(nullptr, nullptr, &response);

EXPECT_EQ(GetParam().first, ActionResult::Result_Name(response.action_result().result()));
EXPECT_EQ(expected_pair.second, response.relative_altitude_m());
}

TEST_F(ActionServiceImplTest, getReturnToLaunchAltitudeDoesNotCrashWithNullResponse)
{
MockAction action;
ActionServiceImpl actionService(action);

actionService.GetReturnToLaunchAltitude(nullptr, nullptr, nullptr);
}

TEST_P(ActionServiceImplTest, setReturnToLaunchAltitudeResultIsTranslatedCorrectly)
{
const auto rpc_result = setReturnToLaunchAltitudeAndGetTranslatedResult(GetParam().second);
EXPECT_EQ(rpc_result, GetParam().first);
}

std::string
setReturnToLaunchAltitudeAndGetTranslatedResult(const dronecode_sdk::ActionResult action_result)
{
MockAction action;
ON_CALL(action, set_return_to_launch_return_altitude(_)).WillByDefault(Return(action_result));
ActionServiceImpl actionService(action);
dronecode_sdk::rpc::action::SetReturnToLaunchAltitudeRequest request;
request.set_relative_altitude_m(ARBITRARY_ALTITUDE);
dronecode_sdk::rpc::action::SetReturnToLaunchAltitudeResponse response;

actionService.SetReturnToLaunchAltitude(nullptr, &request, &response);

return ActionResult::Result_Name(response.action_result().result());
}

TEST_F(ActionServiceImplTest, setReturnToLaunchAltitudeDoesNotCrashWithNullParams)
{
MockAction action;
ActionServiceImpl actionService(action);

actionService.SetReturnToLaunchAltitude(nullptr, nullptr, nullptr);
}

TEST_F(ActionServiceImplTest, setReturnToLaunchAltitudeCallsSetter)
{
MockAction action;
ActionServiceImpl actionService(action);
EXPECT_CALL(action, set_return_to_launch_return_altitude(_)).Times(1);
dronecode_sdk::rpc::action::SetReturnToLaunchAltitudeRequest request;

actionService.SetReturnToLaunchAltitude(nullptr, &request, nullptr);
}

TEST_P(ActionServiceImplTest, setReturnToLaunchAltitudeSetsRightValue)
{
MockAction action;
ActionServiceImpl actionService(action);
float expected_altitude = ARBITRARY_ALTITUDE;
EXPECT_CALL(action, set_return_to_launch_return_altitude(expected_altitude)).Times(1);
dronecode_sdk::rpc::action::SetReturnToLaunchAltitudeRequest request;
request.set_relative_altitude_m(expected_altitude);

actionService.SetReturnToLaunchAltitude(nullptr, &request, nullptr);
}

INSTANTIATE_TEST_CASE_P(ActionResultCorrespondences,
ActionServiceImplTest,
::testing::ValuesIn(generateInputPairs()));
Expand Down
2 changes: 2 additions & 0 deletions plugins/action/mocks/action_mock.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@ class MockAction {
MOCK_CONST_METHOD1(set_takeoff_altitude, ActionResult(float));
MOCK_CONST_METHOD0(get_max_speed, std::pair<ActionResult, float>());
MOCK_CONST_METHOD1(set_max_speed, ActionResult(float));
MOCK_CONST_METHOD0(get_return_to_launch_return_altitude, std::pair<ActionResult, float>());
MOCK_CONST_METHOD1(set_return_to_launch_return_altitude, ActionResult(float));
};

} // namespace testing
Expand Down