Skip to content

Commit

Permalink
POSIX: added hrt_queue for handling fast periodic events
Browse files Browse the repository at this point in the history
The workqueues measure time in ticks  which is typically 10ms.
Some interrupt events in Nuttx occur at about 1ms so a more
granular workqueue is needed for POSIX.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
  • Loading branch information
mcharleb committed Jun 2, 2015
1 parent 9882b78 commit cced8ed
Show file tree
Hide file tree
Showing 5 changed files with 453 additions and 8 deletions.
14 changes: 7 additions & 7 deletions src/platforms/posix/drivers/accelsim/accelsim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -625,18 +625,18 @@ ACCELSIM::ioctl(device::file_t *filp, int cmd, unsigned long arg)
bool want_start = (_call_accel_interval == 0);

/* convert hz to hrt interval via microseconds */
unsigned ticks = 1000000 / arg;
unsigned period = 1000000 / arg;

/* check against maximum sane rate */
if (ticks < 500)
if (period < 500)
return -EINVAL;

/* adjust filters */
accel_set_driver_lowpass_filter((float)arg, _accel_filter_x.get_cutoff_freq());

/* update interval for next measurement */
/* XXX this is a bit shady, but no other way to adjust... */
_accel_call.period = _call_accel_interval = ticks;
_accel_call.period = _call_accel_interval = period;

/* if we need to start the poll state machine, do it */
if (want_start)
Expand Down Expand Up @@ -749,15 +749,15 @@ ACCELSIM::mag_ioctl(device::file_t *filp, int cmd, unsigned long arg)
bool want_start = (_call_mag_interval == 0);

/* convert hz to hrt interval via microseconds */
unsigned ticks = 1000000 / arg;
unsigned period = 1000000 / arg;

/* check against maximum sane rate */
if (ticks < 1000)
/* check against maximum sane rate (1ms) */
if (period < 1000)
return -EINVAL;

/* update interval for next measurement */
/* XXX this is a bit shady, but no other way to adjust... */
_mag_call.period = _call_mag_interval = ticks;
_mag_call.period = _call_mag_interval = period;

/* if we need to start the poll state machine, do it */
if (want_start)
Expand Down
131 changes: 131 additions & 0 deletions src/platforms/posix/px4_layer/hrt_queue.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,131 @@
/****************************************************************************
* libc/wqueue/work_queue.c
*
* Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 NuttX 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.
*
****************************************************************************/

/****************************************************************************
* Included Files
****************************************************************************/

#include <px4_config.h>
#include <px4_defines.h>

#include <signal.h>
#include <stdint.h>
#include <queue.h>
#include <stdio.h>
#include <semaphore.h>
#include <px4_workqueue.h>
#include "hrt_work_lock.h"

#ifdef CONFIG_SCHED_WORKQUEUE

/****************************************************************************
* Pre-processor Definitions
****************************************************************************/

/****************************************************************************
* Private Type Declarations
****************************************************************************/

/****************************************************************************
* Public Variables
****************************************************************************/

/****************************************************************************
* Private Variables
****************************************************************************/

/****************************************************************************
* Private Functions
****************************************************************************/

/****************************************************************************
* Public Functions
****************************************************************************/

/****************************************************************************
* Name: hrt_work_queue
*
* Description:
* Queue work to be performed at a later time. All queued work will be
* performed on the worker thread of of execution (not the caller's).
*
* The work structure is allocated by caller, but completely managed by
* the work queue logic. The caller should never modify the contents of
* the work queue structure; the caller should not call work_queue()
* again until either (1) the previous work has been performed and removed
* from the queue, or (2) work_cancel() has been called to cancel the work
* and remove it from the work queue.
*
* Input parameters:
* work - The work structure to queue
* worker - The worker callback to be invoked. The callback will invoked
* on the worker thread of execution.
* arg - The argument that will be passed to the workder callback when
* int is invoked.
* delay - Delay (in microseconds) from the time queue until the worker
* is invoked. Zero means to perform the work immediately.
*
* Returned Value:
* Zero on success, a negated errno on failure
*
****************************************************************************/

int hrt_work_queue(struct work_s *work, worker_t worker, void *arg, uint32_t delay)
{
struct wqueue_s *wqueue = &hrt_work;

/* First, initialize the work structure */

work->worker = worker; /* Work callback */
work->arg = arg; /* Callback argument */
work->delay = delay; /* Delay until work performed */

/* Now, time-tag that entry and put it in the work queue. This must be
* done with interrupts disabled. This permits this function to be called
* from with task logic or interrupt handlers.
*/

hrt_work_lock();
work->qtime = hrt_absolute_tme(); /* Time work queued */
PX4_INFO("work_queue adding work delay=%u time=%lu", delay, work->qtime);

dq_addlast((dq_entry_t *)work, &wqueue->q);
px4_task_kill(wqueue->pid, SIGCONT); /* Wake up the worker thread */

hrt_work_unlock();
return PX4_OK;
}

#endif /* CONFIG_SCHED_WORKQUEUE */
Loading

0 comments on commit cced8ed

Please sign in to comment.