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

calibration: return only one struct (and the result) #560

Merged
merged 2 commits into from
Oct 1, 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
2 changes: 1 addition & 1 deletion backend/proto
Submodule proto updated from 6edc68 to ad47a0
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 camera mission telemetry)
set(COMPONENTS_LIST core action calibration camera mission telemetry)

include(cmake/compile_proto.cmake)

Expand Down Expand Up @@ -37,6 +37,7 @@ endif()
target_link_libraries(backend
dronecode_sdk
dronecode_sdk_action
dronecode_sdk_calibration
dronecode_sdk_camera
dronecode_sdk_mission
dronecode_sdk_telemetry
Expand Down
2 changes: 2 additions & 0 deletions backend/src/grpc_server.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

#include "plugins/action/action.h"
#include "action/action_service_impl.h"
#include "plugins/calibration/calibration.h"
#include "calibration/calibration_service_impl.h"
#include "plugins/camera/camera.h"
#include "camera/camera_service_impl.h"
#include "core/core_service_impl.h"
Expand Down
167 changes: 167 additions & 0 deletions backend/src/plugins/calibration/calibration_service_impl.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,167 @@
#include <future>

#include "plugins/calibration/calibration.h"
#include "calibration/calibration.grpc.pb.h"

namespace dronecode_sdk {
namespace backend {

template<typename Calibration = Calibration>
class CalibrationServiceImpl final : public rpc::calibration::CalibrationService::Service {
public:
CalibrationServiceImpl(Calibration &calibration) : _calibration(calibration) {}

static std::unique_ptr<rpc::calibration::CalibrationResult>
translateCalibrationResult(const dronecode_sdk::Calibration::Result &calibration_result)
{
auto rpc_calibration_result = std::unique_ptr<rpc::calibration::CalibrationResult>(
new rpc::calibration::CalibrationResult());

auto rpc_result =
static_cast<rpc::calibration::CalibrationResult::Result>(calibration_result);
rpc_calibration_result->set_result(rpc_result);
rpc_calibration_result->set_result_str(
dronecode_sdk::Calibration::result_str(calibration_result));

return rpc_calibration_result;
}

static std::unique_ptr<rpc::calibration::ProgressData>
translateProgressData(const dronecode_sdk::Calibration::ProgressData &progress_data)
{
auto rpc_progress_data =
std::unique_ptr<rpc::calibration::ProgressData>(new rpc::calibration::ProgressData());

rpc_progress_data->set_has_progress(progress_data.has_progress);
rpc_progress_data->set_progress(progress_data.progress);
rpc_progress_data->set_has_status_text(progress_data.has_status_text);
rpc_progress_data->set_status_text(progress_data.status_text);

return rpc_progress_data;
}

grpc::Status
CalibrateGyro(grpc::ServerContext * /* context */,
const rpc::calibration::CalibrateGyroRequest request,
grpc::ServerWriter<rpc::calibration::CalibrateGyroResponse> *writer) override
{
std::promise<void> stream_closed_promise;
auto stream_closed_future = stream_closed_promise.get_future();

bool is_finished = false;

_calibration.calibrate_gyro_async([this, &writer, &stream_closed_promise, &is_finished](
const dronecode_sdk::Calibration::Result result,
const float progress,
const std::string &status_text) {
rpc::calibration::CalibrateGyroResponse rpc_response;
rpc_response.set_allocated_calibration_result(translateCalibrationResult(result).get());

std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
}
});

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

grpc::Status CalibrateAccelerometer(
grpc::ServerContext * /* context */,
const rpc::calibration::CalibrateAccelerometerRequest request,
grpc::ServerWriter<rpc::calibration::CalibrateAccelerometerResponse> *writer) override
{
std::promise<void> stream_closed_promise;
auto stream_closed_future = stream_closed_promise.get_future();

bool is_finished = false;

_calibration.calibrate_accelerometer_async(
[this, &writer, &stream_closed_promise, &is_finished](
const dronecode_sdk::Calibration::Result result,
const float progress,
const std::string &status_text) {
rpc::calibration::CalibrateAccelerometerResponse rpc_response;
rpc_response.set_allocated_calibration_result(
translateCalibrationResult(result).get());

std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
}
});

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

grpc::Status CalibrateMagnetometer(
grpc::ServerContext * /* context */,
const rpc::calibration::CalibrateMagnetometerRequest request,
grpc::ServerWriter<rpc::calibration::CalibrateMagnetometerResponse> *writer) override
{
std::promise<void> stream_closed_promise;
auto stream_closed_future = stream_closed_promise.get_future();

bool is_finished = false;

_calibration.calibrate_magnetometer_async(
[this, &writer, &stream_closed_promise, &is_finished](
const dronecode_sdk::Calibration::Result result,
const float progress,
const std::string &status_text) {
rpc::calibration::CalibrateMagnetometerResponse rpc_response;
rpc_response.set_allocated_calibration_result(
translateCalibrationResult(result).get());

std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
}
});

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

grpc::Status CalibrateGimbalAccelerometer(
grpc::ServerContext * /* context */,
const rpc::calibration::CalibrateGimbalAccelerometerRequest request,
grpc::ServerWriter<rpc::calibration::CalibrateGimbalAccelerometerResponse> *writer) override
{
std::promise<void> stream_closed_promise;
auto stream_closed_future = stream_closed_promise.get_future();

bool is_finished = false;

_calibration.calibrate_gimbal_accelerometer_async(
[this, &writer, &stream_closed_promise, &is_finished](
const dronecode_sdk::Calibration::Result result,
const float progress,
const std::string &status_text) {
rpc::calibration::CalibrateGimbalAccelerometerResponse rpc_response;
rpc_response.set_allocated_calibration_result(
translateCalibrationResult(result).get());

std::lock_guard<std::mutex> lock(_subscribe_mutex);
if (!writer->Write(rpc_response) && !is_finished) {
is_finished = true;
stream_closed_promise.set_value();
}
});

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

private:
Calibration &_calibration;
std::mutex _subscribe_mutex{};
};

} // namespace backend
} // namespace dronecode_sdk
31 changes: 15 additions & 16 deletions integration_tests/calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,9 @@
using namespace dronecode_sdk;
using namespace std::placeholders; // for `_1`

static void receive_calibration_callback(Calibration::Result result,
float progress,
const std::string text,
const std::string calibration_type,
static void receive_calibration_callback(const Calibration::Result result,
const Calibration::ProgressData &progress_data,
julianoes marked this conversation as resolved.
Show resolved Hide resolved
const std::string &calibration_type,
bool &done);

TEST(HardwareTest, CalibrationGyro)
Expand All @@ -30,7 +29,7 @@ TEST(HardwareTest, CalibrationGyro)
bool done = false;

calibration->calibrate_gyro_async(
std::bind(&receive_calibration_callback, _1, _2, _3, "gyro", std::ref(done)));
std::bind(&receive_calibration_callback, _1, _2, "gyro", std::ref(done)));

while (!done) {
std::this_thread::sleep_for(std::chrono::seconds(1));
Expand All @@ -54,7 +53,7 @@ TEST(HardwareTest, CalibrationAccelerometer)
bool done = false;

calibration->calibrate_accelerometer_async(
std::bind(&receive_calibration_callback, _1, _2, _3, "accelerometer", std::ref(done)));
std::bind(&receive_calibration_callback, _1, _2, "accelerometer", std::ref(done)));

while (!done) {
std::this_thread::sleep_for(std::chrono::seconds(1));
Expand All @@ -78,7 +77,7 @@ TEST(HardwareTest, CalibrationMagnetometer)
bool done = false;

calibration->calibrate_magnetometer_async(
std::bind(&receive_calibration_callback, _1, _2, _3, "magnetometer", std::ref(done)));
std::bind(&receive_calibration_callback, _1, _2, "magnetometer", std::ref(done)));

while (!done) {
std::this_thread::sleep_for(std::chrono::seconds(1));
Expand All @@ -101,32 +100,32 @@ TEST(HardwareTest, CalibrationGimbalAccelerometer)

bool done = false;

calibration->calibrate_gimbal_accelerometer_async(std::bind(
&receive_calibration_callback, _1, _2, _3, "gimbal accelerometer", std::ref(done)));
calibration->calibrate_gimbal_accelerometer_async(
std::bind(&receive_calibration_callback, _1, _2, "gimbal accelerometer", std::ref(done)));

while (!done) {
std::this_thread::sleep_for(std::chrono::seconds(1));
}
}

void receive_calibration_callback(Calibration::Result result,
float progress,
const std::string text,
const std::string calibration_type,
void receive_calibration_callback(const Calibration::Result result,
const Calibration::ProgressData &progress_data,
const std::string &calibration_type,
bool &done)
{
if (result == Calibration::Result::IN_PROGRESS) {
LogInfo() << calibration_type << " calibration in progress: " << progress;
LogInfo() << calibration_type << " calibration in progress: " << progress_data.progress;
} else if (result == Calibration::Result::INSTRUCTION) {
LogInfo() << calibration_type << " calibration instruction: " << text;
LogInfo() << calibration_type << " calibration instruction: " << progress_data.status_text;
} else {
EXPECT_EQ(result, Calibration::Result::SUCCESS);

if (result != Calibration::Result::SUCCESS) {
LogErr() << calibration_type
<< " calibration error: " << Calibration::result_str(result);
if (result == Calibration::Result::FAILED) {
LogErr() << calibration_type << " cailbration failed: " << text;
LogErr() << calibration_type
<< " cailbration failed: " << progress_data.status_text;
}
}
done = true;
Expand Down
12 changes: 6 additions & 6 deletions plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,15 +10,15 @@ else()
endif()

add_subdirectory(action)
add_subdirectory(calibration)
add_subdirectory(camera)
add_subdirectory(follow_me)
add_subdirectory(gimbal)
add_subdirectory(info)
add_subdirectory(log_files)
#add_subdirectory(logging) # Not implemented completely
add_subdirectory(mission)
add_subdirectory(offboard)
add_subdirectory(telemetry)
#add_subdirectory(logging) # Not implemented completely
add_subdirectory(log_files)
add_subdirectory(info)
add_subdirectory(follow_me)
add_subdirectory(camera)
add_subdirectory(calibration)

set(UNIT_TEST_SOURCES ${UNIT_TEST_SOURCES} PARENT_SCOPE)
Loading