px4_daemon: fix locking

It was not enough to lock individual accesses to the maps.
For example it could happen that a thread was started and exited very
quickly, before the pthread_t item was inserted into the map, such
that when the cleanup method was called, the thread and pipe fd were not
found (and fd=0=stdin was closed).
This commit is contained in:
Beat Küng 2018-08-06 08:08:40 +02:00 committed by Lorenz Meier
parent 5b171bd614
commit 1f0655302c
3 changed files with 68 additions and 122 deletions

View File

@ -58,7 +58,8 @@ namespace px4_daemon
Server *Server::_instance = nullptr;
Server::Server(int instance_id)
: _instance_id(instance_id)
: _mutex(PTHREAD_MUTEX_INITIALIZER),
_instance_id(instance_id)
{
_instance = this;
}
@ -194,36 +195,53 @@ Server::_execute_cmd_packet(const client_send_packet_s &packet)
args->pipe_fd = pipe_fd;
args->is_atty = packet.payload.execute_msg.is_atty;
if (0 != pthread_create(&new_pthread, NULL, Server::_run_cmd, (void *)args)) {
PX4_ERR("could not start pthread");
_lock(); // need to lock, otherwise the thread could already exit before we insert into the map
ret = pthread_create(&new_pthread, NULL, Server::_run_cmd, (void *)args);
if (ret != 0) {
PX4_ERR("could not start pthread (%i)", ret);
delete args;
return;
} else {
// We won't join the thread, so detach to automatically release resources at its end
pthread_detach(new_pthread);
// We keep two maps for cleanup if a thread is finished or killed.
_client_uuid_to_pthread.insert(std::pair<uint64_t, pthread_t>
(packet.header.client_uuid, new_pthread));
_pthread_to_pipe_fd.insert(std::pair<pthread_t, int>
(new_pthread, pipe_fd));
}
// We keep two maps for cleanup if a thread is finished or killed.
_client_uuid_to_pthread.insert(std::pair<uint64_t, pthread_t>
(packet.header.client_uuid, new_pthread));
_pthread_to_pipe_fd.insert(std::pair<pthread_t, int>
(new_pthread, pipe_fd));
_unlock();
}
void
Server::_kill_cmd_packet(const client_send_packet_s &packet)
{
// TODO: we currently ignore the signal type.
_lock();
pthread_t pthread_to_kill = _client_uuid_to_pthread.get(packet.header.client_uuid);
// TODO: we currently ignore the signal type.
auto client_uuid_iter = _client_uuid_to_pthread.find(packet.header.client_uuid);
if (client_uuid_iter == _client_uuid_to_pthread.end()) {
_unlock();
return;
}
pthread_t pthread_to_kill = client_uuid_iter->second;
// TODO: use a more graceful exit method to avoid resource leaks
int ret = pthread_cancel(pthread_to_kill);
__cleanup_thread(packet.header.client_uuid);
_unlock();
if (ret != 0) {
PX4_ERR("failed to cancel thread");
}
_cleanup_thread(packet.header.client_uuid);
// We don't send retval when we get killed.
// The client knows this and just exits without confirmation.
}
@ -291,9 +309,24 @@ Server::_send_retval(const int pipe_fd, const int retval, const uint64_t client_
void
Server::_cleanup_thread(const uint64_t client_uuid)
{
pthread_t pthread_killed = _client_uuid_to_pthread.get(client_uuid);
int pipe_fd = _pthread_to_pipe_fd.get(pthread_killed);
_lock();
__cleanup_thread(client_uuid);
_unlock();
}
void
Server::__cleanup_thread(const uint64_t client_uuid)
{
pthread_t pthread_killed = _client_uuid_to_pthread[client_uuid];
auto pipe_iter = _pthread_to_pipe_fd.find(pthread_killed);
if (pipe_iter == _pthread_to_pipe_fd.end()) {
// can happen if the thread already exited and then got a kill packet
PX4_DEBUG("pipe fd already closed");
return;
}
int pipe_fd = pipe_iter->second;
close(pipe_fd);
char path[RECV_PIPE_PATH_LEN] = {};

View File

@ -55,7 +55,6 @@
#include <map>
#include "pipe_protocol.h"
#include "threadsafe_map.h"
namespace px4_daemon
@ -100,6 +99,22 @@ private:
void _kill_cmd_packet(const client_send_packet_s &packet);
void _cleanup_thread(const uint64_t client_uuid);
/**
* Like _cleanup_thread(), but does not take the mutex
*/
void __cleanup_thread(const uint64_t client_uuid);
void _lock()
{
pthread_mutex_lock(&_mutex);
}
void _unlock()
{
pthread_mutex_unlock(&_mutex);
}
static void _send_retval(const int pipe_fd, const int retval, const uint64_t client_uuid);
struct RunCmdArgs {
@ -113,13 +128,15 @@ private:
pthread_t _server_main_pthread;
ThreadsafeMap <pthread_t, int> _pthread_to_pipe_fd;
ThreadsafeMap <uint64_t, pthread_t> _client_uuid_to_pthread;
std::map<pthread_t, int> _pthread_to_pipe_fd;
std::map<uint64_t, pthread_t> _client_uuid_to_pthread;
pthread_mutex_t _mutex; ///< protects access to _pthread_to_pipe_fd and _client_uuid_to_pthread
pthread_key_t _key;
int _instance_id; ///< instance ID for running multiple instances of the px4 server
static void _pthread_key_destructor(void *arg);
static Server *_instance;

View File

@ -1,104 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file threadsafe_map.h
*
* This is a small wrapper for std::map to make it thread-safe.
*
* @author Julian Oes <julian@oes.ch>
*/
#pragma once
#include <pthread.h>
#include <map>
namespace px4_daemon
{
template <class Key, class Type>
class ThreadsafeMap
{
public:
ThreadsafeMap() :
_mutex(PTHREAD_MUTEX_INITIALIZER) {};
~ThreadsafeMap() {};
/**
* Insert an entry into the map.
*/
void
insert(std::pair<Key, Type> pair)
{
_lock();
_map.insert(pair);
_unlock();
}
/**
* Get an entry into from the map.
*/
Type get(Key key)
{
// Supposedly locking is not needed to read but since we're
// not sure, let's lock anyway.
_lock();
const Type temp = _map[key];
_unlock();
return temp;
}
void erase(Key key)
{
_lock();
_map.erase(key);
_unlock();
}
private:
void _lock()
{
pthread_mutex_lock(&_mutex);
}
void _unlock()
{
pthread_mutex_unlock(&_mutex);
}
std::map<Key, Type> _map;
pthread_mutex_t _mutex;
};
} // namespace px4_daemon