Skip to content

Commit

Permalink
core: add is_connected interface
Browse files Browse the repository at this point in the history
This adds a sync interface for the connection status of a device. It is
basically the same information as also covered by the async methods
on_discover and on_timeout.
  • Loading branch information
julianoes committed Sep 29, 2017
1 parent ff9aa85 commit 8291e49
Show file tree
Hide file tree
Showing 6 changed files with 66 additions and 1 deletion.
5 changes: 5 additions & 0 deletions core/device_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,11 @@ DeviceImpl::~DeviceImpl()
}
}

bool DeviceImpl::is_connected() const
{
return _heartbeats_arriving;
}

void DeviceImpl::register_mavlink_message_handler(uint16_t msg_id,
mavlink_message_handler_t callback,
const void *cookie)
Expand Down
2 changes: 2 additions & 0 deletions core/device_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,8 @@ class DeviceImpl
static uint8_t get_own_system_id() { return _own_system_id; }
static uint8_t get_own_component_id() { return _own_component_id; }

bool is_connected() const;

// Non-copyable
DeviceImpl(const DeviceImpl &) = delete;
const DeviceImpl &operator=(const DeviceImpl &) = delete;
Expand Down
10 changes: 10 additions & 0 deletions core/dronecore.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,16 @@ Device &DroneCore::device(uint64_t uuid) const
return _impl->get_device(uuid);
}

bool DroneCore::is_connected() const
{
return _impl->is_connected();
}

bool DroneCore::is_connected(uint64_t uuid) const
{
return _impl->is_connected(uuid);
}

void DroneCore::register_on_discover(event_callback_t callback)
{
_impl->register_on_discover(callback);
Expand Down
22 changes: 22 additions & 0 deletions core/dronecore_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,28 @@ Device &DroneCoreImpl::get_device(uint64_t uuid)
return *_devices[system_id];
}

bool DroneCoreImpl::is_connected() const
{
std::lock_guard<std::recursive_mutex> lock(_devices_mutex);

if (_device_impls.size() == 1) {
return _device_impls.begin()->second->is_connected();
}
return false;
}

bool DroneCoreImpl::is_connected(uint64_t uuid) const
{
std::lock_guard<std::recursive_mutex> lock(_devices_mutex);

for (auto it = _device_impls.begin(); it != _device_impls.end(); ++it) {
if (it->second->get_target_uuid() == uuid) {
return it->second->is_connected();
}
}
return false;
}

void DroneCoreImpl::create_device_if_not_existing(uint8_t system_id)
{
std::lock_guard<std::recursive_mutex> lock(_devices_mutex);
Expand Down
5 changes: 4 additions & 1 deletion core/dronecore_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,9 @@ class DroneCoreImpl
Device &get_device();
Device &get_device(uint64_t uuid);

bool is_connected() const;
bool is_connected(uint64_t uuid) const;

void register_on_discover(DroneCore::event_callback_t callback);
void register_on_timeout(DroneCore::event_callback_t callback);

Expand All @@ -38,7 +41,7 @@ class DroneCoreImpl
std::mutex _connections_mutex;
std::vector<Connection *> _connections;

std::recursive_mutex _devices_mutex;
mutable std::recursive_mutex _devices_mutex;
std::map<uint8_t, Device *> _devices;
std::map<uint8_t, DeviceImpl *> _device_impls;

Expand Down
23 changes: 23 additions & 0 deletions include/dronecore.h
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,29 @@ class DroneCore
*/
typedef std::function<void(uint64_t uuid)> event_callback_t;

/**
* @brief Returns true if exactly one device is currently connected.
*
* Connected means we are receiving heartbeats from this device.
* It means the same as "discovered" and "not timed out".
*
* If multiple devices have connected, this will return false.
*
* @return true if exactly one device is connected.
*/
bool is_connected() const;

/**
* @brief Returns true if a device is currently connected.
*
* Connected means we are receiving heartbeats from this device.
* It means the same as "discovered" and "not timed out".
*
* @param uuid UUID of device to check.
* @return true if device is connected.
*/
bool is_connected(uint64_t uuid) const;

/**
* @brief Register callback for device discovery.
*
Expand Down

0 comments on commit 8291e49

Please sign in to comment.