Skip to content

Commit

Permalink
core: Make use of shared pointers (#314)
Browse files Browse the repository at this point in the history
This replaces raw pointers used in connections and devices
by smart pointers. This avoids, freeing them in destructor and also
makes code clean and readable.
  • Loading branch information
Shakthi Prashanth M committed Mar 13, 2018
1 parent ec5694f commit 1e2b53b
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 45 deletions.
65 changes: 23 additions & 42 deletions core/dronecore_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,25 +28,13 @@ DroneCoreImpl::~DroneCoreImpl()
std::lock_guard<std::recursive_mutex> lock(_devices_mutex);
_should_exit = true;

for (auto it = _devices.begin(); it != _devices.end(); ++it) {
delete it->second;
}
_devices.clear();
}

std::vector<Connection *> tmp_connections;
{
std::lock_guard<std::mutex> lock(_connections_mutex);

// We need to copy the connections to a temporary vector. This way they won't
// get used anymore while they are cleaned up.
tmp_connections = _connections;
_connections.clear();
}

for (auto connection : tmp_connections) {
delete connection;
}
}

void DroneCoreImpl::receive_message(const mavlink_message_t &message)
Expand All @@ -71,7 +59,7 @@ void DroneCoreImpl::receive_message(const mavlink_message_t &message)
auto null_device = _devices[0];
_devices.erase(0);
null_device->set_target_system_id(message.sysid);
_devices.insert(std::pair<uint8_t, Device *>(message.sysid, null_device));
_devices.insert(system_entry_t(message.sysid, null_device));
}

create_device_if_not_existing(message.sysid);
Expand Down Expand Up @@ -169,19 +157,16 @@ ConnectionResult DroneCoreImpl::add_link_connection(const std::string &protocol,

ConnectionResult DroneCoreImpl::add_udp_connection(const int local_port_number)
{
Connection *new_connection = new UdpConnection(*this, local_port_number);
ConnectionResult ret = new_connection->start();
std::shared_ptr<Connection> new_conn = std::make_shared<UdpConnection>(*this, local_port_number);

if (ret != ConnectionResult::SUCCESS) {
delete new_connection;
return ret;
ConnectionResult ret = new_conn->start();
if (ret == ConnectionResult::SUCCESS) {
add_connection(new_conn);
}

add_connection(new_connection);
return ConnectionResult::SUCCESS;
return ret;
}

void DroneCoreImpl::add_connection(Connection *new_connection)
void DroneCoreImpl::add_connection(std::shared_ptr<Connection> new_connection)
{
std::lock_guard<std::mutex> lock(_connections_mutex);
_connections.push_back(new_connection);
Expand All @@ -190,32 +175,28 @@ void DroneCoreImpl::add_connection(Connection *new_connection)
ConnectionResult DroneCoreImpl::add_tcp_connection(const std::string &remote_ip,
const int remote_port)
{
Connection *new_connection = new TcpConnection(*this, remote_ip, remote_port);
ConnectionResult ret = new_connection->start();

if (ret != ConnectionResult::SUCCESS) {
delete new_connection;
return ret;
}
std::shared_ptr<Connection> new_conn = std::make_shared<TcpConnection>(*this, remote_ip,
remote_port);

add_connection(new_connection);
return ConnectionResult::SUCCESS;
ConnectionResult ret = new_conn->start();
if (ret == ConnectionResult::SUCCESS) {
add_connection(new_conn);
}
return ret;
}

ConnectionResult DroneCoreImpl::add_serial_connection(const std::string &dev_path,
const int baudrate)
{
#if !defined(WINDOWS) && !defined(APPLE)
Connection *new_connection = new SerialConnection(*this, dev_path, baudrate);
ConnectionResult ret = new_connection->start();

if (ret != ConnectionResult::SUCCESS) {
delete new_connection;
return ret;
std::shared_ptr<Connection> new_conn = std::make_shared<SerialConnection>(*this,
dev_path, baudrate);
ConnectionResult ret = new_conn->start();
if (ret == ConnectionResult::SUCCESS) {
add_connection(new_conn);
}

add_connection(new_connection);
return ConnectionResult::SUCCESS;
return ret;
#else
UNUSED(dev_path);
UNUSED(baudrate);
Expand Down Expand Up @@ -329,9 +310,9 @@ void DroneCoreImpl::create_device_if_not_existing(const uint8_t system_id)
return;
}

// Create both lists in parallel
Device *new_device = new Device(*this, system_id);
_devices.insert(std::pair<uint8_t, Device *>(system_id, new_device));
// Make new device
auto new_device = std::make_shared<Device>(*this, system_id);
_devices.insert(system_entry_t(system_id, new_device));
}

void DroneCoreImpl::notify_on_discover(const uint64_t uuid)
Expand Down
8 changes: 5 additions & 3 deletions core/dronecore_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class DroneCoreImpl
ConnectionResult add_link_connection(const std::string &protocol, const std::string &ip,
int port);
ConnectionResult add_udp_connection(int local_port_number);
void add_connection(Connection *connection);
void add_connection(std::shared_ptr<Connection>);
ConnectionResult add_tcp_connection(const std::string &remote_ip, int remote_port);
ConnectionResult add_serial_connection(const std::string &dev_path, int baudrate);

Expand All @@ -43,11 +43,13 @@ class DroneCoreImpl
private:
void create_device_if_not_existing(uint8_t system_id);

using system_entry_t = std::pair<uint8_t, std::shared_ptr<Device>>;

std::mutex _connections_mutex;
std::vector<Connection *> _connections;
std::vector<std::shared_ptr<Connection>> _connections;

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

DroneCore::event_callback_t _on_discover_callback;
DroneCore::event_callback_t _on_timeout_callback;
Expand Down

0 comments on commit 1e2b53b

Please sign in to comment.