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

Fix #547 Add callback for components discovered. #556

Merged
merged 10 commits into from
Oct 1, 2018
14 changes: 14 additions & 0 deletions core/include/system.h
Original file line number Diff line number Diff line change
@@ -1,9 +1,15 @@
#pragma once

#include <memory>
#include <functional>

namespace dronecode_sdk {

/**
* @brief type for component discovery callback
*/
typedef std::function<void(uint8_t)> discover_callback_t;

class SystemImpl;
class DronecodeSDKImpl;
class PluginImplBase;
Expand Down Expand Up @@ -76,6 +82,14 @@ class System {
*/
uint64_t get_uuid() const;

/**
* @brief Register a callback to be called when a component is discovered.
*
* @param callback a function of type void(uint8_t) which will be called with the COMPONENT_ID
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would prefer if we don't "leak" the mavlink component ID outside of the SDK but only the notion of autopilot/camera/gimbal. Therefore, in my opinion, it should be something like register_camera_discovered().

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is there a convention on how components should be called? I mean how do you know, from MAVLink, that it is a camera?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The camera has MAV_COMP_ID_CAMERA[x], it's something known to the SDK internals.

https://mavlink.io/en/messages/common.html#MAV_COMP_ID_CAMERA

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@julianoes Can we declare an enum like ::Camera ::Gimbal ::AutoPilot ::Unknown etc (maybe this already exists and pass that to the callback? that way there'd only be one callback function instead of one function per component.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes an enum for components makes sense, I agree.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@julianoes change pushed.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Cool, the comment needs to be adapted though.

* of the new component.
*/
void register_component_discovered_callback(discover_callback_t callback) const;

/**
* @brief Copy constructor (object is not copyable).
*/
Expand Down
5 changes: 5 additions & 0 deletions core/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,4 +53,9 @@ uint64_t System::get_uuid() const
return _system_impl->get_uuid();
}

void System::register_component_discovered_callback(discover_callback_t callback) const
{
return _system_impl->register_component_discovered_callback(callback);
}

} // namespace dronecode_sdk
11 changes: 11 additions & 0 deletions core/system_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ SystemImpl::SystemImpl(DronecodeSDKImpl &parent, uint8_t system_id, uint8_t comp
_call_every_handler(_time),
_thread_pool(3)
{
component_discovered_callback = nullptr;

_system_thread = new std::thread(&SystemImpl::system_thread, this);

register_mavlink_message_handler(
Expand Down Expand Up @@ -332,6 +334,10 @@ void SystemImpl::add_new_component(uint8_t component_id)
{
auto res_pair = _components.insert(component_id);
if (res_pair.second) {
if (component_discovered_callback != nullptr) {
call_user_callback(
[this, component_id]() { component_discovered_callback(component_id); });
}
LogDebug() << "Component " << component_name(component_id) << " added.";
}
}
Expand All @@ -341,6 +347,11 @@ size_t SystemImpl::total_components() const
return _components.size();
}

void SystemImpl::register_component_discovered_callback(discover_callback_t callback)
JonasVautherin marked this conversation as resolved.
Show resolved Hide resolved
{
component_discovered_callback = callback;
}

bool SystemImpl::is_standalone() const
{
return !has_autopilot();
Expand Down
3 changes: 3 additions & 0 deletions core/system_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include "timeout_handler.h"
#include "call_every_handler.h"
#include "thread_pool.h"
#include "system.h"
#include <cstdint>
#include <functional>
#include <atomic>
Expand Down Expand Up @@ -96,6 +97,8 @@ class SystemImpl {
// Adds unique component ids
void add_new_component(uint8_t component_id);
size_t total_components() const;
void register_component_discovered_callback(discover_callback_t callback);
discover_callback_t component_discovered_callback;

uint8_t get_autopilot_id() const;
std::vector<uint8_t> get_camera_ids() const;
Expand Down
20 changes: 15 additions & 5 deletions example/takeoff_land/takeoff_and_land.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,12 @@ void usage(std::string bin_name)
<< "For example, to connect to the simulator use URL: udp://:14540" << std::endl;
}

void component_discovered(uint8_t component_id)
{
std::cout << NORMAL_CONSOLE_TEXT << "Discovered a component with ID " << unsigned(component_id)
<< std::endl;
}

int main(int argc, char **argv)
{
DronecodeSDK dc;
Expand All @@ -51,6 +57,15 @@ int main(int argc, char **argv)
return 1;
}

// We don't need to specify the UUID if it's only one system anyway.
JonasVautherin marked this conversation as resolved.
Show resolved Hide resolved
// If there were multiple, we could specify it with:
// dc.system(uint64_t uuid);
System &system = dc.system();

// Register a callback so we get told when components (camera, gimbal) etc
// are found.
system.register_component_discovered_callback(component_discovered);

std::cout << "Waiting to discover system..." << std::endl;
dc.register_on_discover([&discovered_system](uint64_t uuid) {
std::cout << "Discovered system with UUID: " << uuid << std::endl;
Expand All @@ -67,11 +82,6 @@ int main(int argc, char **argv)
return 1;
}

// We don't need to specify the UUID if it's only one system anyway.
// If there were multiple, we could specify it with:
// dc.system(uint64_t uuid);
System &system = dc.system();

auto telemetry = std::make_shared<Telemetry>(system);
auto action = std::make_shared<Action>(system);

Expand Down