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 Param #686

Merged
merged 9 commits into from
Mar 8, 2019
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
2 changes: 1 addition & 1 deletion .ycm_extra_conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@
'-I',
'plugins/offboard/include',
'-I',
'plugins/params_raw/include',
'plugins/param/include',
'-I',
'plugins/telemetry/include',
'-I',
Expand Down
2 changes: 1 addition & 1 deletion backend/proto
Submodule proto updated from 222023 to bcb4b6
3 changes: 2 additions & 1 deletion backend/src/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 3.1)

set(COMPONENTS_LIST core action calibration gimbal camera mission telemetry info)
set(COMPONENTS_LIST core action calibration gimbal camera mission telemetry info param)

include(cmake/compile_proto.cmake)

Expand Down Expand Up @@ -43,6 +43,7 @@ target_link_libraries(backend
dronecode_sdk_mission
dronecode_sdk_telemetry
dronecode_sdk_info
dronecode_sdk_param
gRPC::grpc++
)

Expand Down
11 changes: 9 additions & 2 deletions backend/src/core/core_service_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,15 @@ class CoreServiceImpl final : public dronecode_sdk::rpc::core::CoreService::Serv
const rpc::core::ListRunningPluginsRequest * /* request */,
dronecode_sdk::rpc::core::ListRunningPluginsResponse *response) override
{
std::string plugin_names[8] = {
"action", "calibration", "gimbal", "camera", "core", "mission", "telemetry", "info"};
std::string plugin_names[9] = {"action",
"calibration",
"camera",
"core",
"gimbal",
"info",
"mission",
"param",
"telemetry"};

for (const auto plugin_name : plugin_names) {
auto plugin_info = response->add_plugin_info();
Expand Down
1 change: 1 addition & 0 deletions backend/src/grpc_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ void GRPCServer::run()
builder.RegisterService(&_mission_service);
builder.RegisterService(&_telemetry_service);
builder.RegisterService(&_info_service);
builder.RegisterService(&_param_service);

_server = builder.BuildAndStart();
LogInfo() << "Server started";
Expand Down
8 changes: 7 additions & 1 deletion backend/src/grpc_server.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
#include "info/info_service_impl.h"
#include "plugins/gimbal/gimbal.h"
#include "gimbal/gimbal_service_impl.h"
#include "plugins/param/param.h"
#include "param/param_service_impl.h"

namespace dronecode_sdk {
namespace backend {
Expand All @@ -39,7 +41,9 @@ class GRPCServer {
_telemetry(_dc.system()),
_telemetry_service(_telemetry),
_info(_dc.system()),
_info_service(_info)
_info_service(_info),
_param(_dc.system()),
_param_service(_param)
{}

void run();
Expand All @@ -65,6 +69,8 @@ class GRPCServer {
TelemetryServiceImpl<> _telemetry_service;
Info _info;
InfoServiceImpl<> _info_service;
Param _param;
ParamServiceImpl<> _param_service;

std::unique_ptr<grpc::Server> _server;
};
Expand Down
113 changes: 113 additions & 0 deletions backend/src/plugins/param/param_service_impl.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,113 @@
#include "plugins/param/param.h"
#include "param/param.grpc.pb.h"

namespace dronecode_sdk {
namespace backend {

template<typename Param = Param>
class ParamServiceImpl final : public rpc::param::ParamService::Service {
public:
ParamServiceImpl(Param &param) : _param(param) {}

grpc::Status GetIntParam(grpc::ServerContext * /* context */,
const rpc::param::GetIntParamRequest *request,
rpc::param::GetIntParamResponse *response) override
{
if (request != nullptr) {
const auto requested_param = request->name();

if (response != nullptr) {
auto result_pair = _param.get_param_int(requested_param);

auto *rpc_param_result = new rpc::param::ParamResult();
rpc_param_result->set_result(
static_cast<rpc::param::ParamResult::Result>(result_pair.first));
rpc_param_result->set_result_str(
dronecode_sdk::Param::result_str(result_pair.first));

response->set_allocated_param_result(rpc_param_result);
response->set_value(result_pair.second);
}
}

return grpc::Status::OK;
}

grpc::Status SetIntParam(grpc::ServerContext * /* context */,
const rpc::param::SetIntParamRequest *request,
rpc::param::SetIntParamResponse *response) override
{
if (request != nullptr) {
const auto requested_param_name = request->name();
const auto requested_param_value = request->value();

const auto param_result =
_param.set_param_int(requested_param_name, requested_param_value);

if (response != nullptr) {
auto *rpc_param_result = new rpc::param::ParamResult();
rpc_param_result->set_result(
static_cast<rpc::param::ParamResult::Result>(param_result));
rpc_param_result->set_result_str(dronecode_sdk::Param::result_str(param_result));

response->set_allocated_param_result(rpc_param_result);
}
}

return grpc::Status::OK;
}

grpc::Status GetFloatParam(grpc::ServerContext * /* context */,
const rpc::param::GetFloatParamRequest *request,
rpc::param::GetFloatParamResponse *response) override
{
if (request != nullptr) {
const auto requested_param = request->name();

if (response != nullptr) {
auto result_pair = _param.get_param_float(requested_param);

auto *rpc_param_result = new rpc::param::ParamResult();
rpc_param_result->set_result(
static_cast<rpc::param::ParamResult::Result>(result_pair.first));
rpc_param_result->set_result_str(
dronecode_sdk::Param::result_str(result_pair.first));

response->set_allocated_param_result(rpc_param_result);
response->set_value(result_pair.second);
}
}

return grpc::Status::OK;
}

grpc::Status SetFloatParam(grpc::ServerContext * /* context */,
const rpc::param::SetFloatParamRequest *request,
rpc::param::SetFloatParamResponse *response) override
{
if (request != nullptr) {
const auto requested_param_name = request->name();
const auto requested_param_value = request->value();

const auto param_result =
_param.set_param_float(requested_param_name, requested_param_value);

if (response != nullptr) {
auto *rpc_param_result = new rpc::param::ParamResult();
rpc_param_result->set_result(
static_cast<rpc::param::ParamResult::Result>(param_result));
rpc_param_result->set_result_str(dronecode_sdk::Param::result_str(param_result));

response->set_allocated_param_result(rpc_param_result);
}
}

return grpc::Status::OK;
}

private:
Param &_param;
};

} // namespace backend
} // namespace dronecode_sdk
4 changes: 2 additions & 2 deletions integration_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ add_executable(integration_tests_runner
mission_survey.cpp
mission_raw_mission_changed.cpp
offboard_velocity.cpp
params_raw.cpp
param.cpp
path_checker.cpp
path_checker.h
system_connection_async.cpp
Expand Down Expand Up @@ -83,7 +83,7 @@ target_link_libraries(integration_tests_runner
dronecode_sdk_follow_me
dronecode_sdk_camera
dronecode_sdk_calibration
dronecode_sdk_params_raw
dronecode_sdk_param
${additional_libs}
gtest
gtest_main
Expand Down
6 changes: 3 additions & 3 deletions integration_tests/calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include "global_include.h"
#include "dronecode_sdk.h"
#include "plugins/calibration/calibration.h"
#include "plugins/params_raw/params_raw.h"
#include "plugins/param/param.h"
#include "plugins/telemetry/telemetry.h"

using namespace dronecode_sdk;
Expand Down Expand Up @@ -136,8 +136,8 @@ TEST(HardwareTest, CalibrationGyroWithTelemetry)
ASSERT_TRUE(system.has_autopilot());

// Reset Gyro calibration using param.
auto params_raw = std::make_shared<ParamsRaw>(system);
params_raw->set_param_int("CAL_GYRO0_ID", 0);
auto param = std::make_shared<Param>(system);
param->set_param_int("CAL_GYRO0_ID", 0);

// Make sure telemetry reports gyro calibration as false.
auto telemetry = std::make_shared<Telemetry>(system);
Expand Down
119 changes: 119 additions & 0 deletions integration_tests/param.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,119 @@
#include <iostream>
#include "integration_test_helper.h"
#include "dronecode_sdk.h"
#include "plugins/param/param.h"

using namespace dronecode_sdk;

TEST_F(SitlTest, ParamSad)
{
DronecodeSDK dc;

ConnectionResult ret = dc.add_udp_connection();
ASSERT_EQ(ret, ConnectionResult::SUCCESS);

// Wait for system to connect via heartbeat.
std::this_thread::sleep_for(std::chrono::seconds(2));

auto &system = dc.system();
ASSERT_TRUE(system.has_autopilot());

auto param = std::make_shared<Param>(system);

{
const std::pair<Param::Result, float> get_result = param->get_param_float("SYS_HITL");
EXPECT_EQ(get_result.first, Param::Result::WRONG_TYPE);
}

{
const std::pair<Param::Result, int32_t> get_result = param->get_param_int("MPC_VEL_MANUAL");
EXPECT_EQ(get_result.first, Param::Result::WRONG_TYPE);
}

{
const std::pair<Param::Result, int32_t> get_result =
param->get_param_int("NAME_TOO_LOOOOONG");
EXPECT_EQ(get_result.first, Param::Result::PARAM_NAME_TOO_LONG);
}
}

TEST_F(SitlTest, ParamHappy)
{
DronecodeSDK dc;

ConnectionResult ret = dc.add_udp_connection();
ASSERT_EQ(ret, ConnectionResult::SUCCESS);

// Wait for system to connect via heartbeat.
std::this_thread::sleep_for(std::chrono::seconds(2));

auto &system = dc.system();
ASSERT_TRUE(system.has_autopilot());

auto param = std::make_shared<Param>(system);

{
const std::pair<Param::Result, int> get_result1 = param->get_param_int("SYS_HITL");

// Get initial value.
ASSERT_EQ(get_result1.first, Param::Result::SUCCESS);
ASSERT_GE(get_result1.second, 0);
ASSERT_LE(get_result1.second, 1);

std::this_thread::sleep_for(std::chrono::seconds(1));

// Toggle the value.
const Param::Result set_result1 = param->set_param_int("SYS_HITL", !get_result1.second);
EXPECT_EQ(set_result1, Param::Result::SUCCESS);

// Verify toggle.
const std::pair<Param::Result, int> get_result2 = param->get_param_int("SYS_HITL");
EXPECT_EQ(get_result2.first, Param::Result::SUCCESS);
EXPECT_EQ(get_result2.second, !get_result1.second);

std::this_thread::sleep_for(std::chrono::seconds(1));

// Reset back to initial value.
const Param::Result set_result2 = param->set_param_int("SYS_HITL", get_result1.second);
EXPECT_EQ(set_result2, Param::Result::SUCCESS);

// Verify reset.
const std::pair<Param::Result, int> get_result3 = param->get_param_int("SYS_HITL");
EXPECT_EQ(get_result3.first, Param::Result::SUCCESS);
EXPECT_EQ(get_result3.second, get_result1.second);
}

{
const std::pair<Param::Result, float> get_result1 =
param->get_param_float("MPC_VEL_MANUAL");

// Get initial value.
ASSERT_EQ(get_result1.first, Param::Result::SUCCESS);

std::this_thread::sleep_for(std::chrono::seconds(1));

// Toggle the value.
const Param::Result set_result1 =
param->set_param_float("MPC_VEL_MANUAL", get_result1.second + 1.0f);
EXPECT_EQ(set_result1, Param::Result::SUCCESS);

// Verify toggle.
const std::pair<Param::Result, float> get_result2 =
param->get_param_float("MPC_VEL_MANUAL");
EXPECT_EQ(get_result2.first, Param::Result::SUCCESS);
EXPECT_FLOAT_EQ(get_result2.second, get_result1.second + 1.0f);

std::this_thread::sleep_for(std::chrono::seconds(1));

// Reset back to initial value.
const Param::Result set_result2 =
param->set_param_float("MPC_VEL_MANUAL", get_result1.second);
EXPECT_EQ(set_result2, Param::Result::SUCCESS);

// Verify reset.
const std::pair<Param::Result, float> get_result3 =
param->get_param_float("MPC_VEL_MANUAL");
EXPECT_EQ(get_result3.first, Param::Result::SUCCESS);
EXPECT_FLOAT_EQ(get_result3.second, get_result1.second);
}
}
Loading