From cb152bbcd52d6cd84163c6bdf9adaad6290419b6 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 25 Jul 2018 18:56:30 +0200 Subject: [PATCH] backend: WIP for getter/setter API changes --- .../src/plugins/action/action_service_impl.h | 36 ++++++++++++++---- backend/test/action_service_impl_test.cpp | 37 +++++++++++-------- plugins/action/mocks/action_mock.h | 8 ++-- 3 files changed, 53 insertions(+), 28 deletions(-) diff --git a/backend/src/plugins/action/action_service_impl.h b/backend/src/plugins/action/action_service_impl.h index f257655685..6a7107def6 100644 --- a/backend/src/plugins/action/action_service_impl.h +++ b/backend/src/plugins/action/action_service_impl.h @@ -132,8 +132,15 @@ class ActionServiceImpl final : public rpc::action::ActionService::Service { rpc::action::GetTakeoffAltitudeResponse *response) override { if (response != nullptr) { - auto takeoff_altitude = _action.get_takeoff_altitude_m(); - response->set_altitude_m(takeoff_altitude); + auto result_pair = _action.get_takeoff_altitude(); + + auto *rpc_action_result = new rpc::action::ActionResult(); + rpc_action_result->set_result( + static_cast(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_altitude(result_pair.second); } return grpc::Status::OK; @@ -145,7 +152,7 @@ class ActionServiceImpl final : public rpc::action::ActionService::Service { rpc::action::SetTakeoffAltitudeResponse * /* response */) override { if (request != nullptr) { - const auto requested_altitude = request->altitude_m(); + const auto requested_altitude = request->altitude(); _action.set_takeoff_altitude(requested_altitude); } @@ -157,8 +164,15 @@ class ActionServiceImpl final : public rpc::action::ActionService::Service { rpc::action::GetMaximumSpeedResponse *response) override { if (response != nullptr) { - auto max_speed = _action.get_max_speed_m_s(); - response->set_speed_m_s(max_speed); + auto result_pair = _action.get_max_speed(); + + auto *rpc_action_result = new rpc::action::ActionResult(); + rpc_action_result->set_result( + static_cast(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_speed(result_pair.second); } return grpc::Status::OK; @@ -166,11 +180,17 @@ class ActionServiceImpl final : public rpc::action::ActionService::Service { grpc::Status SetMaximumSpeed(grpc::ServerContext * /* context */, const rpc::action::SetMaximumSpeedRequest *request, - rpc::action::SetMaximumSpeedResponse * /* response */) override + rpc::action::SetMaximumSpeedResponse *response) override { if (request != nullptr) { - const auto requested_speed = request->speed_m_s(); - _action.set_max_speed(requested_speed); + const auto requested_speed = request->speed(); + ActionResult action_result = _action.set_max_speed(requested_speed); + + auto *rpc_action_result = new rpc::action::ActionResult(); + rpc_action_result->set_result( + static_cast(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; diff --git a/backend/test/action_service_impl_test.cpp b/backend/test/action_service_impl_test.cpp index c4a8bd3f98..ffae954ca5 100644 --- a/backend/test/action_service_impl_test.cpp +++ b/backend/test/action_service_impl_test.cpp @@ -18,8 +18,8 @@ using ActionServiceImpl = dronecode_sdk::backend::ActionServiceImpl; using ActionResult = dronecode_sdk::rpc::action::ActionResult; using InputPair = std::pair; -static constexpr auto ARBITRARY_ALTITUDE = 42.42f; -static constexpr auto ARBITRARY_SPEED = 8.24f; +static constexpr float ARBITRARY_ALTITUDE = 42.42f; +static constexpr float ARBITRARY_SPEED = 8.24f; std::vector generateInputPairs(); std::string armAndGetTranslatedResult(dronecode_sdk::ActionResult arm_result); @@ -257,23 +257,25 @@ TEST_F(ActionServiceImplTest, getTakeoffAltitudeCallsGetter) { MockAction action; ActionServiceImpl actionService(action); - EXPECT_CALL(action, get_takeoff_altitude_m()).Times(1); + EXPECT_CALL(action, get_takeoff_altitude()).Times(1); dronecode_sdk::rpc::action::GetTakeoffAltitudeResponse response; actionService.GetTakeoffAltitude(nullptr, nullptr, &response); } -TEST_F(ActionServiceImplTest, getsCorrectTakeoffAltitude) +TEST_P(ActionServiceImplTest, getsCorrectTakeoffAltitude) { MockAction action; ActionServiceImpl actionService(action); - const float expected_altitude = ARBITRARY_ALTITUDE; - ON_CALL(action, get_takeoff_altitude_m()).WillByDefault(Return(expected_altitude)); + const auto expected_pair = + std::make_pair<>(dronecode_sdk::ActionResult::SUCCESS, ARBITRARY_ALTITUDE); + ON_CALL(action, get_takeoff_altitude()).WillByDefault(Return(expected_pair)); dronecode_sdk::rpc::action::GetTakeoffAltitudeResponse response; actionService.GetTakeoffAltitude(nullptr, nullptr, &response); - EXPECT_EQ(expected_altitude, response.altitude_m()); + EXPECT_EQ(GetParam().first, ActionResult::Result_Name(response.action_result().result())); + EXPECT_EQ(expected_pair.second, response.altitude()); } TEST_F(ActionServiceImplTest, getTakeoffAltitudeDoesNotCrashWithNullResponse) @@ -302,14 +304,14 @@ TEST_F(ActionServiceImplTest, setTakeoffAltitudeCallsSetter) actionService.SetTakeoffAltitude(nullptr, &request, nullptr); } -TEST_F(ActionServiceImplTest, setTakeoffAltitudeSetsRightValue) +TEST_P(ActionServiceImplTest, setTakeoffAltitudeSetsRightValue) { MockAction action; ActionServiceImpl actionService(action); float expected_altitude = ARBITRARY_ALTITUDE; EXPECT_CALL(action, set_takeoff_altitude(expected_altitude)).Times(1); dronecode_sdk::rpc::action::SetTakeoffAltitudeRequest request; - request.set_altitude_m(expected_altitude); + request.set_altitude(expected_altitude); actionService.SetTakeoffAltitude(nullptr, &request, nullptr); } @@ -326,23 +328,25 @@ TEST_F(ActionServiceImplTest, getMaxSpeedCallsGetter) { MockAction action; ActionServiceImpl actionService(action); - EXPECT_CALL(action, get_max_speed_m_s()).Times(1); + EXPECT_CALL(action, get_max_speed()).Times(1); dronecode_sdk::rpc::action::GetMaximumSpeedResponse response; actionService.GetMaximumSpeed(nullptr, nullptr, &response); } -TEST_F(ActionServiceImplTest, getMaxSpeedGetsRightValue) +TEST_P(ActionServiceImplTest, getMaxSpeedGetsRightValue) { MockAction action; ActionServiceImpl actionService(action); - const auto expected_max_speed = ARBITRARY_SPEED; - ON_CALL(action, get_max_speed_m_s()).WillByDefault(Return(expected_max_speed)); + const auto expected_pair = + std::make_pair<>(dronecode_sdk::ActionResult::SUCCESS, ARBITRARY_SPEED); + ON_CALL(action, get_max_speed()).WillByDefault(Return(expected_pair)); dronecode_sdk::rpc::action::GetMaximumSpeedResponse response; actionService.GetMaximumSpeed(nullptr, nullptr, &response); - EXPECT_EQ(expected_max_speed, response.speed_m_s()); + EXPECT_EQ(GetParam().first, ActionResult::Result_Name(response.action_result().result())); + EXPECT_EQ(expected_pair.second, response.speed()); } TEST_F(ActionServiceImplTest, setMaxSpeedDoesNotCrashWithNullRequest) @@ -357,7 +361,8 @@ TEST_F(ActionServiceImplTest, setMaxSpeedCallsSetter) { MockAction action; ActionServiceImpl actionService(action); - EXPECT_CALL(action, set_max_speed(_)).Times(1); + const auto expected_speed = ARBITRARY_SPEED; + EXPECT_CALL(action, set_max_speed(expected_speed)).Times(1); dronecode_sdk::rpc::action::SetMaximumSpeedRequest request; actionService.SetMaximumSpeed(nullptr, &request, nullptr); @@ -370,7 +375,7 @@ TEST_F(ActionServiceImplTest, setMaxSpeedSetsRightValue) const auto expected_speed = ARBITRARY_SPEED; EXPECT_CALL(action, set_max_speed(expected_speed)).Times(1); dronecode_sdk::rpc::action::SetMaximumSpeedRequest request; - request.set_speed_m_s(expected_speed); + request.set_speed(expected_speed); actionService.SetMaximumSpeed(nullptr, &request, nullptr); } diff --git a/plugins/action/mocks/action_mock.h b/plugins/action/mocks/action_mock.h index 255422f142..1438f156b3 100644 --- a/plugins/action/mocks/action_mock.h +++ b/plugins/action/mocks/action_mock.h @@ -15,10 +15,10 @@ class MockAction { MOCK_CONST_METHOD0(return_to_launch, ActionResult()); MOCK_CONST_METHOD0(transition_to_fixedwing, ActionResult()); MOCK_CONST_METHOD0(transition_to_multicopter, ActionResult()); - MOCK_CONST_METHOD0(get_takeoff_altitude_m, float()); - MOCK_CONST_METHOD1(set_takeoff_altitude, void(float)); - MOCK_CONST_METHOD0(get_max_speed_m_s, float()); - MOCK_CONST_METHOD1(set_max_speed, void(float)); + MOCK_CONST_METHOD0(get_takeoff_altitude, std::pair()); + MOCK_CONST_METHOD1(set_takeoff_altitude, ActionResult(float)); + MOCK_CONST_METHOD0(get_max_speed, std::pair()); + MOCK_CONST_METHOD1(set_max_speed, ActionResult(float)); }; } // namespace testing