Skip to content

Commit

Permalink
PX4 general work queue
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar committed Mar 2, 2019
1 parent dc50a56 commit a3086e2
Show file tree
Hide file tree
Showing 31 changed files with 1,810 additions and 16 deletions.
2 changes: 1 addition & 1 deletion .ci/Jenkinsfile-compile
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ pipeline {
]

def nuttx_builds_other = [
target: ["px4_cannode-v1_default", "px4_esc-v1_default", "thiemar_s2740vc-v1_default"],
target: ["px4_esc-v1_default", "thiemar_s2740vc-v1_default"],
image: docker_images.nuttx,
archive: false
]
Expand Down
1 change: 1 addition & 0 deletions platforms/nuttx/src/px4_layer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ if (NOT ${PX4_BOARD} MATCHES "px4_io")
nuttx_apps # up_cxxinitialize
nuttx_sched
drivers_boards_common_arch
px4_work_queue
)
else()
add_library(px4_layer ${PX4_SOURCE_DIR}/src/platforms/empty.c)
Expand Down
3 changes: 3 additions & 0 deletions platforms/nuttx/src/px4_layer/px4_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include <px4_defines.h>
#include <drivers/drv_hrt.h>
#include <lib/parameters/param.h>
#include <px4_work_queue/WorkQueueManager.hpp>
#include <systemlib/cpuload.h>

#include <fcntl.h>
Expand Down Expand Up @@ -104,5 +105,7 @@ int px4_platform_init(void)
cpuload_initialize_once();
#endif

px4::WorkQueueManagerStart();

return PX4_OK;
}
7 changes: 4 additions & 3 deletions platforms/posix/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -62,10 +62,11 @@ else()
${df_driver_libs}
df_driver_framework
pthread m

# horrible circular dependencies that need to be teased apart
px4_layer
px4_platform
px4_layer px4_platform
work_queue
parameters
)

if (NOT APPLE)
Expand Down
2 changes: 1 addition & 1 deletion platforms/posix/src/px4_layer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ add_library(px4_layer
${SHMEM_SRCS}
)
target_compile_definitions(px4_layer PRIVATE MODULE_NAME="px4")
target_link_libraries(px4_layer PRIVATE work_queue)
target_link_libraries(px4_layer PRIVATE work_queue px4_work_queue)
target_link_libraries(px4_layer PRIVATE px4_daemon)

if(ENABLE_LOCKSTEP_SCHEDULER)
Expand Down
3 changes: 3 additions & 0 deletions platforms/posix/src/px4_layer/px4_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,12 +37,15 @@
#include <px4_defines.h>
#include <drivers/drv_hrt.h>
#include <lib/parameters/param.h>
#include <px4_work_queue/WorkQueueManager.hpp>

int px4_platform_init(void)
{
hrt_init();

param_init();

px4::WorkQueueManagerStart();

return PX4_OK;
}
3 changes: 3 additions & 0 deletions platforms/qurt/src/px4_layer/px4_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,12 +37,15 @@
#include <px4_defines.h>
#include <drivers/drv_hrt.h>
#include <lib/parameters/param.h>
#include <px4_work_queue/WorkQueueManager.hpp>

int px4_platform_init(void)
{
hrt_init();

param_init();

px4::WorkQueueManagerStart();

return PX4_OK;
}
2 changes: 1 addition & 1 deletion posix-configs/SITL/init/test/cmd_template.in
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ mavlink start -x -u 14556 -r 2000000
mavlink boot_complete

@cmd_name@ start
sleep 1
sleep 3
@cmd_name@ start
sleep 1
@cmd_name@ stop
Expand Down
173 changes: 173 additions & 0 deletions src/include/containers/BlockingList.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,173 @@
/****************************************************************************
*
* Copyright (C) 2019 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 BlockingList.hpp
*
* A blocking intrusive linked list.
*/

#pragma once

#include <pthread.h>
#include <stdlib.h>

#include "LockGuard.hpp"

template<class T>
class BlockingListNode
{
public:

void setSibling(T sibling) { _blocking_list_node_sibling = sibling; }
const T getSibling() const { return _blocking_list_node_sibling; }

protected:

T _blocking_list_node_sibling{nullptr};

};

template<class T>
class BlockingList
{
public:

~BlockingList()
{
pthread_mutex_destroy(&_mutex);
pthread_cond_destroy(&_cv);
}

void add(T newNode)
{
LockGuard lg{_mutex};
newNode->setSibling(getHead());
_head = newNode;
}

bool remove(T removeNode)
{
LockGuard lg{_mutex};

// base case
if (removeNode == _head) {
_head = nullptr;
return true;
}

for (T node = getHead(); node != nullptr; node = node->getSibling()) {
// is sibling the node to remove?
if (node->getSibling() == removeNode) {
// replace sibling
if (node->getSibling() != nullptr) {
node->setSibling(node->getSibling()->getSibling());

} else {
node->setSibling(nullptr);
}

return true;
}
}

return false;
}

struct Iterator {
T node;
Iterator(T v) : node(v) {}

operator T() const { return node; }
operator T &() { return node; }
T operator* () const { return node; }
Iterator &operator++ ()
{
if (node) {
node = node->getSibling();
};

return *this;
}
};

Iterator begin() { return Iterator(getHead()); }
Iterator end() { return Iterator(nullptr); }

const T getHead() const { return _head; }

bool empty() const { return getHead() == nullptr; }

size_t size() const
{
LockGuard lg{_mutex};
size_t sz = 0;

for (auto node = getHead(); node != nullptr; node = node->getSibling()) {
sz++;
}

return sz;
}

void deleteNode(T node)
{
if (remove(node)) {
// only delete if node was successfully removed
delete node;
}
}

void clear()
{
LockGuard lg{_mutex};
auto node = getHead();

while (node != nullptr) {
auto next = node->getSibling();
delete node;
node = next;
}

_head = nullptr;
}

LockGuard getLockGuard() { return LockGuard{_mutex}; }

private:

pthread_mutex_t _mutex = PTHREAD_MUTEX_INITIALIZER;
pthread_cond_t _cv = PTHREAD_COND_INITIALIZER;

T _head{nullptr};
};
97 changes: 97 additions & 0 deletions src/include/containers/BlockingQueue.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
/****************************************************************************
*
* Copyright (C) 2019 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.
*
****************************************************************************/

#pragma once

#include <pthread.h>

#include "LockGuard.hpp"

template<class T, size_t N>
class BlockingQueue
{
public:

BlockingQueue() = default;

~BlockingQueue()
{
pthread_mutex_destroy(&_mutex);
pthread_cond_destroy(&_cv);
}

bool empty() const { return _count == 0; }
bool full() const { return _count == N; }

void push(T newItem)
{
LockGuard lg(_mutex);

if (full()) {
pthread_cond_wait(&_cv, &_mutex);
}

_data[_tail] = newItem;
_tail = (_tail + 1) % N;
_count++;

pthread_cond_signal(&_cv);
}

T pop()
{
LockGuard lg(_mutex);

if (empty()) {
pthread_cond_wait(&_cv, &_mutex);
}

T ret = _data[_head];
_head = (_head + 1) % N;
_count--;

return ret;
}

private:

pthread_mutex_t _mutex = PTHREAD_MUTEX_INITIALIZER;
pthread_cond_t _cv = PTHREAD_COND_INITIALIZER;

T _data[N];
size_t _count{0};

size_t _head{0};
size_t _tail{0};

};
6 changes: 3 additions & 3 deletions src/include/containers/List.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,12 @@ class ListNode
{
public:

void setSibling(T sibling) { _sibling = sibling; }
const T getSibling() const { return _sibling; }
void setSibling(T sibling) { _list_node_sibling = sibling; }
const T getSibling() const { return _list_node_sibling; }

protected:

T _sibling{nullptr};
T _list_node_sibling{nullptr};

};

Expand Down
Loading

0 comments on commit a3086e2

Please sign in to comment.