Skip to content

Commit

Permalink
WIP server component
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Apr 8, 2022
1 parent 99ad051 commit 668ed0f
Show file tree
Hide file tree
Showing 21 changed files with 444 additions and 256 deletions.
2 changes: 2 additions & 0 deletions src/mavsdk/core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ target_sources(mavsdk
ping.cpp
plugin_impl_base.cpp
serial_connection.cpp
server_component_impl.cpp
server_plugin_impl_base.cpp
tcp_connection.cpp
timeout_handler.cpp
udp_connection.cpp
Expand Down
20 changes: 20 additions & 0 deletions src/mavsdk/core/include/mavsdk/server_component.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#pragma once

namespace mavsdk {

class ServerComponentImpl;

/**
* TODO: add comments
*/
class ServerComponent {
public:
private:
std::shared_ptr<ServerComponentImpl> server_component_impl() { return _server_component_impl; };

std::shared_ptr<ServerComponentImpl> _server_component_impl;

friend ServerPluginImplBase;
};

} // namespace mavsdk
33 changes: 33 additions & 0 deletions src/mavsdk/core/include/mavsdk/server_plugin_base.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
#pragma once
#include "server_component_impl.h"
#include <memory>

namespace mavsdk {

class ServerComponent;
class ServerComponentImpl;

class ServerPluginBase {
public:
/**
* @brief Default Constructor.
*/
ServerPluginBase() = default;

/**
* @brief Default Destructor.
*/
virtual ~ServerPluginBase() = default;

/**
* @brief Copy constructor (object is not copyable).
*/
ServerPluginBase(const ServerPluginBase&) = delete;

/**
* @brief Assign operator (object is not copyable).
*/
const ServerPluginBase& operator=(const ServerPluginBase&) = delete;
};

} // namespace mavsdk
14 changes: 7 additions & 7 deletions src/mavsdk/core/mavlink_command_receiver.cpp
Original file line number Diff line number Diff line change
@@ -1,19 +1,19 @@
#include "mavlink_command_receiver.h"
#include "system_impl.h"
#include "mavsdk_impl.h"
#include <cmath>
#include <future>
#include <memory>

namespace mavsdk {

MavlinkCommandReceiver::MavlinkCommandReceiver(SystemImpl& system_impl) : _parent(system_impl)
MavlinkCommandReceiver::MavlinkCommandReceiver(MavsdkImpl& mavsdk_impl) : _mavsdk_impl(mavsdk_impl)
{
_parent.register_mavlink_message_handler(
_mavsdk_impl.mavlink_message_handler.register_one(
MAVLINK_MSG_ID_COMMAND_LONG,
[this](const mavlink_message_t& message) { receive_command_long(message); },
this);

_parent.register_mavlink_message_handler(
_mavsdk_impl.mavlink_message_handler.register_one(
MAVLINK_MSG_ID_COMMAND_INT,
[this](const mavlink_message_t& message) { receive_command_int(message); },
this);
Expand All @@ -23,7 +23,7 @@ MavlinkCommandReceiver::~MavlinkCommandReceiver()
{
unregister_all_mavlink_command_handlers(this);

_parent.unregister_all_mavlink_message_handlers(this);
_mavsdk_impl.mavlink_message_handler.unregister_all(this);
}

void MavlinkCommandReceiver::receive_command_int(const mavlink_message_t& message)
Expand All @@ -37,7 +37,7 @@ void MavlinkCommandReceiver::receive_command_int(const mavlink_message_t& messag
// The client side can pack a COMMAND_ACK as a response to receiving the command.
auto maybe_message = handler.callback(cmd);
if (maybe_message) {
_parent.send_message(maybe_message.value());
_mavsdk_impl.send_message(maybe_message.value());
}
}
}
Expand All @@ -54,7 +54,7 @@ void MavlinkCommandReceiver::receive_command_long(const mavlink_message_t& messa
// The client side can pack a COMMAND_ACK as a response to receiving the command.
auto maybe_message = handler.callback(cmd);
if (maybe_message) {
_parent.send_message(maybe_message.value());
_mavsdk_impl.send_message(maybe_message.value());
}
}
}
Expand Down
6 changes: 3 additions & 3 deletions src/mavsdk/core/mavlink_command_receiver.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,11 @@

namespace mavsdk {

class SystemImpl;
class MavsdkImpl;

class MavlinkCommandReceiver {
public:
explicit MavlinkCommandReceiver(SystemImpl& system_impl);
explicit MavlinkCommandReceiver(MavsdkImpl& mavsdk_impl);
~MavlinkCommandReceiver();

struct CommandInt {
Expand Down Expand Up @@ -115,7 +115,7 @@ class MavlinkCommandReceiver {
void unregister_all_mavlink_command_handlers(const void* cookie);

private:
SystemImpl& _parent;
MavsdkImpl& _mavsdk_impl;

void receive_command_int(const mavlink_message_t& message);
void receive_command_long(const mavlink_message_t& message);
Expand Down
2 changes: 1 addition & 1 deletion src/mavsdk/core/mavlink_mission_transfer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ namespace mavsdk {

MavlinkMissionTransfer::MavlinkMissionTransfer(
Sender& sender,
MAVLinkMessageHandler& message_handler,
MavlinkMessageHandler& message_handler,
TimeoutHandler& timeout_handler,
TimeoutSCallback timeout_s_callback) :
_sender(sender),
Expand Down
5 changes: 3 additions & 2 deletions src/mavsdk/core/mavsdk_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,13 +238,14 @@ void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connect

if (_should_exit) {
// Don't try to call at() if systems have already been destroyed
// in descructor.
// in destructor.
return;
}

for (auto& system : _systems) {
if (system.first == message.sysid) {
system.second->system_impl()->process_mavlink_message(message);
//system.second->system_impl()->process_mavlink_message(message);
mavlink_message_handler.process_message(message);
break;
}
}
Expand Down
4 changes: 4 additions & 0 deletions src/mavsdk/core/mavsdk_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include "mavsdk.h"
#include "mavlink_include.h"
#include "mavlink_address.h"
#include "mavlink_message_handler.h"
#include "safe_queue.h"
#include "system.h"
#include "timeout_handler.h"
Expand Down Expand Up @@ -92,6 +93,9 @@ class MavsdkImpl {
void set_custom_mode(uint32_t custom_mode);
uint32_t get_custom_mode() const;

MavlinkMessageHandler mavlink_message_handler{};
Time time{};

private:
void add_connection(const std::shared_ptr<Connection>&);
void make_system_with_component(
Expand Down
2 changes: 1 addition & 1 deletion src/mavsdk/core/plugin_impl_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class PluginImplBase {
* when a system is constructed. This does not mean that the system actually
* exists and is connected, it might just be an empty dummy system.
*
* Plugins should do initialization steps with other parts of the Dronecode SDK
* Plugins should do initialization steps with other parts of MAVSDK
* at this state, e.g. set up callbacks with _parent (System).
*/
virtual void init() = 0;
Expand Down
107 changes: 107 additions & 0 deletions src/mavsdk/core/server_component_impl.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
#include "server_component_impl.h"
#include "mavsdk_impl.h"

namespace mavsdk {

ServerComponentImpl::ServerComponentImpl(MavsdkImpl& mavsdk_impl) :
_mavsdk_impl(mavsdk_impl),
_mavlink_command_receiver(mavsdk_impl)
{

}

ServerComponentImpl::~ServerComponentImpl()
{
}

void ServerComponentImpl::register_mavlink_command_handler(
uint16_t cmd_id,
const MavlinkCommandReceiver::MavlinkCommandIntHandler& callback,
const void* cookie)
{
_mavlink_command_receiver.register_mavlink_command_handler(cmd_id, callback, cookie);
}

void ServerComponentImpl::register_mavlink_command_handler(
uint16_t cmd_id,
const MavlinkCommandReceiver::MavlinkCommandLongHandler& callback,
const void* cookie)
{
_mavlink_command_receiver.register_mavlink_command_handler(cmd_id, callback, cookie);
}

void ServerComponentImpl::unregister_mavlink_command_handler(uint16_t cmd_id, const void* cookie)
{
_mavlink_command_receiver.unregister_mavlink_command_handler(cmd_id, cookie);
}

void ServerComponentImpl::unregister_all_mavlink_command_handlers(const void* cookie)
{
_mavlink_command_receiver.unregister_all_mavlink_command_handlers(cookie);
}

uint8_t ServerComponentImpl::get_own_system_id() const
{
return _mavsdk_impl.get_own_system_id();
}

void ServerComponentImpl::set_own_component_id(uint8_t own_component_id)
{
_own_component_id = own_component_id;
}
uint8_t ServerComponentImpl::get_own_component_id() const
{
return _own_component_id;
}

Time& ServerComponentImpl::get_time()
{
return _mavsdk_impl.time;
}

bool ServerComponentImpl::send_message(mavlink_message_t& message)
{
return _mavsdk_impl.send_message(message);
}

void ServerComponentImpl::add_call_every(std::function<void()> callback, float interval_s, void** cookie)
{
_mavsdk_impl.call_every_handler.add(std::move(callback), static_cast<double>(interval_s), cookie);
}

void ServerComponentImpl::change_call_every(float interval_s, const void* cookie)
{
_mavsdk_impl.call_every_handler.change(static_cast<double>(interval_s), cookie);
}

void ServerComponentImpl::reset_call_every(const void* cookie)
{
_mavsdk_impl.call_every_handler.reset(cookie);
}

void ServerComponentImpl::remove_call_every(const void* cookie)
{
_mavsdk_impl.call_every_handler.remove(cookie);
}

mavlink_message_t ServerComponentImpl::make_command_ack_message(
const MavlinkCommandReceiver::CommandLong& command, MAV_RESULT result)
{
const uint8_t progress = std::numeric_limits<uint8_t>::max();
const uint8_t result_param2 = 0;

mavlink_message_t msg{};
mavlink_msg_command_ack_pack(
get_own_system_id(),
get_own_component_id(),
&msg,
command.command,
result,
progress,
result_param2,
command.origin_system_id,
command.origin_component_id);
return msg;
}

} // namespace mavsdk
51 changes: 51 additions & 0 deletions src/mavsdk/core/server_component_impl.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
#pragma once

#include <cstdint>
#include "mavlink_include.h"
#include "mavlink_command_receiver.h"
#include "mavsdk_time.h"

namespace mavsdk {

class MavsdkImpl;

class ServerComponentImpl {
public:
explicit ServerComponentImpl(MavsdkImpl& parent);
~ServerComponentImpl();

void register_mavlink_command_handler(
uint16_t cmd_id,
const MavlinkCommandReceiver::MavlinkCommandIntHandler& callback,
const void* cookie);
void register_mavlink_command_handler(
uint16_t cmd_id,
const MavlinkCommandReceiver::MavlinkCommandLongHandler& callback,
const void* cookie);
void unregister_mavlink_command_handler(uint16_t cmd_id, const void* cookie);
void unregister_all_mavlink_command_handlers(const void* cookie);

uint8_t get_own_system_id() const;

void set_own_component_id(uint8_t own_component_id);
uint8_t get_own_component_id() const;

Time& get_time();

bool send_message(mavlink_message_t& message);

void add_call_every(std::function<void()> callback, float interval_s, void** cookie);
void change_call_every(float interval_s, const void* cookie);
void reset_call_every(const void* cookie);
void remove_call_every(const void* cookie);

mavlink_message_t
make_command_ack_message(const MavlinkCommandReceiver::CommandLong& command, MAV_RESULT result);

private:
MavsdkImpl& _mavsdk_impl;
MavlinkCommandReceiver _mavlink_command_receiver;
uint8_t _own_component_id{MAV_COMP_ID_AUTOPILOT1};
};

} // namespace mavsdk
10 changes: 10 additions & 0 deletions src/mavsdk/core/server_plugin_impl_base.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#include "server_plugin_impl_base.h"
#include "server_component.h"

namespace mavsdk {

ServerPluginImplBase::ServerPluginImplBase(std::shared_ptr<ServerComponent> server_component) :
_server_component_impl(server_component->server_component_impl())
{}

} // namespace mavsdk
Loading

0 comments on commit 668ed0f

Please sign in to comment.