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

Enable backend to accept connection URL #730

Merged
merged 2 commits into from
Apr 28, 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
8 changes: 4 additions & 4 deletions backend/src/backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@ class DronecodeSDKBackend::Impl {
Impl() {}
~Impl() {}

void connect(const int mavlink_listen_port)
void connect(const std::string &connection_url)
{
_connection_initiator.start(_dc, 14540);
_connection_initiator.start(_dc, connection_url);
_connection_initiator.wait();
}

Expand All @@ -41,9 +41,9 @@ void DronecodeSDKBackend::startGRPCServer()
{
_impl->startGRPCServer();
}
void DronecodeSDKBackend::connect(const int mavlink_listen_port)
void DronecodeSDKBackend::connect(const std::string &connection_url)
{
return _impl->connect(mavlink_listen_port);
return _impl->connect(connection_url);
}
void DronecodeSDKBackend::wait()
{
Expand Down
3 changes: 2 additions & 1 deletion backend/src/backend.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include <memory>
#include <string>

namespace dronecode_sdk {
namespace backend {
Expand All @@ -13,7 +14,7 @@ class DronecodeSDKBackend {
DronecodeSDKBackend &operator=(DronecodeSDKBackend &&) = delete;

void startGRPCServer();
void connect(const int mavlink_listen_port = 14540);
void connect(const std::string &connection_url = "udp://");
void wait();

private:
Expand Down
6 changes: 3 additions & 3 deletions backend/src/backend_api.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
#include "backend_api.h"

#include "backend.h"
#include <string>

void runBackend(const int mavlink_listen_port, void (*onServerStarted)(void *), void *context)
void runBackend(const char *connection_url, void (*onServerStarted)(void *), void *context)
{
dronecode_sdk::backend::DronecodeSDKBackend backend;
backend.startGRPCServer();
backend.connect(mavlink_listen_port);
backend.connect(std::string(connection_url));

if (onServerStarted != nullptr) {
onServerStarted(context);
Expand Down
2 changes: 1 addition & 1 deletion backend/src/backend_api.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ extern "C" {
#endif

__attribute__((visibility("default"))) void
runBackend(int mavlink_listen_port, void (*onServerStarted)(void *), void *context);
runBackend(const char *connection_url, void (*onServerStarted)(void *), void *context);

#ifdef __cplusplus
}
Expand Down
9 changes: 5 additions & 4 deletions backend/src/connection_initiator.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include <future>
#include <string>

#include "connection_result.h"
#include "log.h"
Expand All @@ -13,14 +14,14 @@ template<typename DronecodeSDK> class ConnectionInitiator {
ConnectionInitiator() {}
~ConnectionInitiator() {}

bool start(DronecodeSDK &dc, const int port)
bool start(DronecodeSDK &dc, const std::string &connection_url)
{
init_mutex();
init_timeout_logging(dc);

_discovery_future = wrapped_register_on_discover(dc);

if (!add_udp_connection(dc, port)) {
if (!add_any_connection(dc, connection_url)) {
return false;
}

Expand All @@ -38,9 +39,9 @@ template<typename DronecodeSDK> class ConnectionInitiator {
[](uint64_t uuid) { LogInfo() << "System timed out [UUID: " << uuid << "]"; });
}

bool add_udp_connection(DronecodeSDK &dc, const int port)
bool add_any_connection(DronecodeSDK &dc, const std::string &connection_url)
{
dronecode_sdk::ConnectionResult connection_result = dc.add_udp_connection(port);
dronecode_sdk::ConnectionResult connection_result = dc.add_any_connection(connection_url);

if (connection_result != ConnectionResult::SUCCESS) {
LogErr() << "Connection failed: " << connection_result_str(connection_result);
Expand Down
38 changes: 37 additions & 1 deletion backend/src/dronecode_sdk_server.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,42 @@
#include "backend_api.h"
#include <iostream>
#include <string>

static void usage();

static auto constexpr default_connection = "udp://:14540";

int main(int argc, char **argv)
{
runBackend(14540, nullptr, nullptr);
if (argc > 2) {
usage();
return 1;
}

if (argc == 2) {
const std::string positional_arg = argv[1];
if (positional_arg.compare("-h") == 0 || positional_arg.compare("--help") == 0) {
usage();
return 0;
}
runBackend(positional_arg.c_str(), nullptr, nullptr);
}

runBackend(default_connection, nullptr, nullptr);
}

void usage()
{
std::cout << "Usage: backend_bin [-h | --help]" << std::endl
<< " backend_bin [Connection URL]" << std::endl
<< std::endl
<< "Connection URL format should be:" << std::endl
<< " Serial: serial:///path/to/serial/dev[:baudrate]" << std::endl
<< " UDP: udp://[bind_host][:bind_port]" << std::endl
<< " TCP: tcp://[server_host][:server_port]" << std::endl
<< std::endl
<< "For example to connect to SITL use: udp://:14540" << std::endl
<< std::endl
<< "Options:" << std::endl
<< " -h | --help : show this help" << std::endl;
}
14 changes: 7 additions & 7 deletions backend/test/connection_initiator_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ using event_callback_t = dronecode_sdk::testing::event_callback_t;
using MockDronecodeSDK = NiceMock<dronecode_sdk::testing::MockDronecodeSDK>;
using ConnectionInitiator = dronecode_sdk::backend::ConnectionInitiator<MockDronecodeSDK>;

static constexpr auto ARBITRARY_PORT = 1291;
static constexpr auto ARBITRARY_CONNECTION_URL = "udp://1291";
static constexpr auto ARBITRARY_UUID = 1492;

ACTION_P(SaveCallback, event_callback)
Expand All @@ -27,17 +27,17 @@ TEST(ConnectionInitiator, registerDiscoverIsCalledExactlyOnce)
MockDronecodeSDK dc;
EXPECT_CALL(dc, register_on_discover(_)).Times(1);

initiator.start(dc, ARBITRARY_PORT);
initiator.start(dc, ARBITRARY_CONNECTION_URL);
}

TEST(ConnectionInitiator, startAddsUDPConnection)
{
ConnectionInitiator initiator;
MockDronecodeSDK dc;

EXPECT_CALL(dc, add_udp_connection(_));
EXPECT_CALL(dc, add_any_connection(_));

initiator.start(dc, ARBITRARY_PORT);
initiator.start(dc, ARBITRARY_CONNECTION_URL);
}

TEST(ConnectionInitiator, startHangsUntilSystemDiscovered)
Expand All @@ -48,7 +48,7 @@ TEST(ConnectionInitiator, startHangsUntilSystemDiscovered)
EXPECT_CALL(dc, register_on_discover(_)).WillOnce(SaveCallback(&discover_callback));

auto async_future = std::async(std::launch::async, [&initiator, &dc]() {
initiator.start(dc, ARBITRARY_PORT);
initiator.start(dc, ARBITRARY_CONNECTION_URL);
initiator.wait();
});

Expand All @@ -65,7 +65,7 @@ TEST(ConnectionInitiator, connectionDetectedIfDiscoverCallbackCalledBeforeWait)
event_callback_t discover_callback;
EXPECT_CALL(dc, register_on_discover(_)).WillOnce(SaveCallback(&discover_callback));

initiator.start(dc, ARBITRARY_PORT);
initiator.start(dc, ARBITRARY_CONNECTION_URL);
discover_callback(ARBITRARY_UUID);
initiator.wait();
}
Expand All @@ -77,7 +77,7 @@ TEST(ConnectionInitiator, doesNotCrashIfDiscoverCallbackCalledMoreThanOnce)
event_callback_t discover_callback;
EXPECT_CALL(dc, register_on_discover(_)).WillOnce(SaveCallback(&discover_callback));

initiator.start(dc, ARBITRARY_PORT);
initiator.start(dc, ARBITRARY_CONNECTION_URL);
discover_callback(ARBITRARY_UUID);
discover_callback(ARBITRARY_UUID);
}
Expand Down
3 changes: 2 additions & 1 deletion core/mocks/dronecode_sdk_mock.h
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include <string>
#include <gmock/gmock.h>

#include "connection_result.h"
Expand All @@ -9,7 +10,7 @@ typedef std::function<void(uint64_t uuid)> event_callback_t;

class MockDronecodeSDK {
public:
MOCK_CONST_METHOD1(add_udp_connection, ConnectionResult(int local_port_number)){};
MOCK_CONST_METHOD1(add_any_connection, ConnectionResult(const std::string &)){};
MOCK_CONST_METHOD1(register_on_discover, void(event_callback_t)){};
MOCK_CONST_METHOD1(register_on_timeout, void(event_callback_t)){};
};
Expand Down