Nuttx Upgrade:Adds sem_setprotocol

This commit is contained in:
David Sidrane 2016-12-12 03:22:22 -10:00 committed by Lorenz Meier
parent 8610eced57
commit c9f10107c0
11 changed files with 80 additions and 14 deletions

View File

@ -278,8 +278,12 @@ extern "C" {
}
PX4_DEBUG("Called px4_poll timeout = %d", timeout);
px4_sem_init(&sem, 0, 0);
// sem use case is a signal
px4_sem_setprotocol(&sem, SEM_PRIO_NONE);
// Go through all fds and check them for a pollable state
bool fd_pollable = false;
@ -409,6 +413,11 @@ extern "C" {
void px4_enable_sim_lockstep()
{
px4_sem_init(&lockstep_sem, 0, 0);
// lockstep_sem use case is a signal
px4_sem_setprotocol(&lockstep_sem, SEM_PRIO_NONE);
sim_lockstep = true;
sim_delay = false;
}

View File

@ -231,6 +231,9 @@ PX4IO_serial::~PX4IO_serial()
px4_arch_unconfiggpio(PX4IO_SERIAL_TX_GPIO);
px4_arch_unconfiggpio(PX4IO_SERIAL_RX_GPIO);
/* Disable APB clock for the USART peripheral */
modifyreg32(STM32_RCC_APB2ENR, RCC_APB2ENR_USART6EN, 0);
/* and kill our semaphores */
px4_sem_destroy(&_completion_semaphore);
px4_sem_destroy(&_bus_semaphore);
@ -263,6 +266,10 @@ PX4IO_serial::init()
return -1;
}
/* Enable the APB clock for the USART peripheral */
modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_USART6EN);
/* configure pins for serial use */
px4_arch_configgpio(PX4IO_SERIAL_TX_GPIO);
px4_arch_configgpio(PX4IO_SERIAL_RX_GPIO);
@ -294,6 +301,11 @@ PX4IO_serial::init()
/* create semaphores */
px4_sem_init(&_completion_semaphore, 0, 0);
/* _completion_semaphore use case is a signal */
px4_sem_setprotocol(&_completion_semaphore, SEM_PRIO_NONE);
px4_sem_init(&_bus_semaphore, 0, 1);
@ -311,7 +323,7 @@ PX4IO_serial::ioctl(unsigned operation, unsigned &arg)
case 1: /* XXX magic number - test operation */
switch (arg) {
case 0:
lowsyslog("test 0\n");
syslog(LOG_INFO, "test 0\n");
/* kill DMA, this is a PIO test */
stm32_dmastop(_tx_dma);
@ -338,7 +350,7 @@ PX4IO_serial::ioctl(unsigned operation, unsigned &arg)
}
if (count >= 5000) {
lowsyslog("==== test 1 : %u failures ====\n", fails);
syslog(LOG_INFO, "==== test 1 : %u failures ====\n", fails);
perf_print_counter(_pc_txns);
perf_print_counter(_pc_dmasetup);
perf_print_counter(_pc_retries);
@ -357,7 +369,7 @@ PX4IO_serial::ioctl(unsigned operation, unsigned &arg)
}
case 2:
lowsyslog("test 2\n");
syslog(LOG_INFO, "test 2\n");
return 0;
}
@ -597,7 +609,7 @@ PX4IO_serial::_wait_complete()
}
/* we might? see this for EINTR */
lowsyslog("unexpected ret %d/%d\n", ret, errno);
syslog(LOG_ERR, "unexpected ret %d/%d\n", ret, errno);
}
/* reset DMA status */

View File

@ -274,6 +274,10 @@ create_work_item(void)
/* If we got one then lock the item*/
if (item) {
px4_sem_init(&item->wait_sem, 1, 0); /* Caller will wait on this... initially locked */
/* item->wait_sem use case is a signal */
px4_sem_setprotocol(&item->wait_sem, SEM_PRIO_NONE);
}
/* return the item pointer, or NULL if all failed */
@ -922,6 +926,10 @@ task_main(int argc, char *argv[])
px4_sem_init(&g_work_queued_sema, 1, 0);
/* g_work_queued_sema use case is a signal */
px4_sem_setprotocol(&g_work_queued_sema, SEM_PRIO_NONE);
if (!on_disk) {
/* In memory */
@ -1135,6 +1143,10 @@ start(void)
px4_sem_init(&g_init_sema, 1, 0);
/* g_init_sema use case is a signal */
px4_sem_setprotocol(&g_init_sema, SEM_PRIO_NONE);
/* start the worker thread with low priority for disk IO */
if ((task = px4_task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT - 10, 1200, task_main, NULL)) <= 0) {
warn("task start failed");

View File

@ -723,6 +723,12 @@ void Logger::run()
memset(&timer_call, 0, sizeof(hrt_call));
px4_sem_t timer_semaphore;
px4_sem_init(&timer_semaphore, 0, 0);
/* timer_semaphore use case is a signal */
px4_sem_setprotocol(&timer_semaphore, SEM_PRIO_NONE);
hrt_call_every(&timer_call, _log_interval, _log_interval, timer_callback, &timer_semaphore);
// check for new subscription data

View File

@ -222,6 +222,8 @@ private: // data members
Semaphore()
{
sem_init(&_Sem, 0, 0);
/* _Sem use case is a signal */
px4_sem_setprotocol(&_Sem, SEM_PRIO_NONE);
}
~Semaphore()
{

View File

@ -107,6 +107,8 @@ Syslink::Syslink() :
_bstate(BAT_DISCHARGING)
{
px4_sem_init(&memory_sem, 0, 0);
/* memory_sem use case is a signal */
px4_sem_setprotocol(&memory_sem, SEM_PRIO_NONE);
}

View File

@ -110,6 +110,8 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys
if (res < 0) {
std::abort();
}
/* _server_command_sem use case is a signal */
px4_sem_setprotocol(&_server_command_sem, SEM_PRIO_NONE);
if (_perfcnt_node_spin_elapsed == nullptr) {
errx(1, "uavcan: couldn't allocate _perfcnt_node_spin_elapsed");

View File

@ -345,19 +345,23 @@ class VirtualCanDriver : public uavcan::ICanDriver,
{
class Event
{
FAR sem_t sem;
FAR px4_sem_t sem;
public:
int init()
{
return sem_init(&sem, 0, 0);
int rv = px4_sem_init(&sem, 0, 0);
if (rv == 0) {
px4_sem_setprotocol(&sem, SEM_PRIO_NONE);
}
return rv;
}
int deinit()
{
return sem_destroy(&sem);
return px4_sem_destroy(&sem);
}
@ -388,7 +392,7 @@ class VirtualCanDriver : public uavcan::ICanDriver,
abstime.tv_nsec -= NsPerSec;
}
(void)sem_timedwait(&sem, &abstime);
(void)px4_sem_timedwait(&sem, &abstime);
}
}
}
@ -396,7 +400,7 @@ class VirtualCanDriver : public uavcan::ICanDriver,
void signal()
{
int count;
int rv = sem_getvalue(&sem, &count);
int rv = px4_sem_getvalue(&sem, &count);
if (rv > 0 && count <= 0) {
px4_sem_post(&sem);

View File

@ -60,6 +60,11 @@ int px4_sem_init(px4_sem_t *s, int pshared, unsigned value)
return 0;
}
int px4_sem_setprotocol(px4_sem_t *s, int protocol)
{
return 0;
}
int px4_sem_wait(px4_sem_t *s)
{
int ret = pthread_mutex_lock(&(s->lock));

View File

@ -41,6 +41,14 @@
#include <semaphore.h>
#if !defined(__PX4_NUTTX)
/* Values for protocol attribute */
#define SEM_PRIO_NONE 0
#define SEM_PRIO_INHERIT 1
#define SEM_PRIO_PROTECT 2
#define sem_setprotocol(s,p)
#endif
#ifdef __PX4_DARWIN
@ -53,6 +61,7 @@ typedef struct {
} px4_sem_t;
__EXPORT int px4_sem_init(px4_sem_t *s, int pshared, unsigned value);
__EXPORT int px4_sem_setprotocol(px4_sem_t *s, int protocol);
__EXPORT int px4_sem_wait(px4_sem_t *s);
__EXPORT int px4_sem_timedwait(px4_sem_t *sem, const struct timespec *abstime);
__EXPORT int px4_sem_post(px4_sem_t *s);
@ -67,11 +76,12 @@ __BEGIN_DECLS
typedef sem_t px4_sem_t;
#define px4_sem_init sem_init
#define px4_sem_wait sem_wait
#define px4_sem_post sem_post
#define px4_sem_getvalue sem_getvalue
#define px4_sem_destroy sem_destroy
#define px4_sem_init sem_init
#define px4_sem_setprotocol sem_setprotocol
#define px4_sem_wait sem_wait
#define px4_sem_post sem_post
#define px4_sem_getvalue sem_getvalue
#define px4_sem_destroy sem_destroy
#ifdef __PX4_QURT
__EXPORT int px4_sem_timedwait(px4_sem_t *sem, const struct timespec *abstime);

View File

@ -171,6 +171,8 @@ int test_dataman(int argc, char *argv[])
av[0] = a;
av[1] = 0;
px4_sem_init(sems + i, 1, 0);
/* sems use case is a signal */
px4_sem_setprotocol(&sems, SEM_PRIO_NONE);
/* start the task */
if ((task = px4_task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, (void *)av)) <= 0) {