aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDavid Sidrane <david_s5@nscdg.com>2015-04-21 12:58:14 -1000
committerDavid Sidrane <david_s5@nscdg.com>2015-04-22 02:30:14 -1000
commitb051a7571fe2be93243cd808f81546a9b25ac989 (patch)
tree8eebf2ad9187825aba4d258f3a9b3b04f6eba12e
parent3f287843a374f585c51292b7ae676a8b3d01e8e1 (diff)
downloadpx4-firmware-b051a7571fe2be93243cd808f81546a9b25ac989.tar.gz
px4-firmware-b051a7571fe2be93243cd808f81546a9b25ac989.tar.bz2
px4-firmware-b051a7571fe2be93243cd808f81546a9b25ac989.zip
Documantation pass
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/flash.c71
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/flash.h4
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/timer.c372
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/timer.h303
4 files changed, 688 insertions, 62 deletions
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/flash.c b/src/drivers/boards/px4cannode-v1/bootloader/src/flash.c
index de0522281..dffd2c3c5 100644
--- a/src/drivers/boards/px4cannode-v1/bootloader/src/flash.c
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/flash.c
@@ -1,4 +1,45 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2015 PX4 Development Team. All rights reserved.
+ * Author: Ben Dyer <ben_dyer@mac.com>
+ * Pavel Kirienko <pavel.kirienko@zubax.com>
+ * David Sidrane <david_s5@nscdg.com>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
#include <nuttx/config.h>
+
#include "board_config.h"
#include <stdint.h>
@@ -11,8 +52,34 @@
#include "flash.h"
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
* Name: bl_flash_erase
*
* Description:
@@ -22,7 +89,7 @@
* address - The address of the flash to erase
*
* Returned value:
- * On sucess FLASH_OK On Error one of the flash_error_t
+ * On success FLASH_OK On Error one of the flash_error_t
*
****************************************************************************/
@@ -77,7 +144,7 @@ flash_error_t bl_flash_erase(size_t address)
* to the flash.
*
* Returned value:
- * On sucess FLASH_OK On Error one of the flash_error_t
+ * On success FLASH_OK On Error one of the flash_error_t
*
****************************************************************************/
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/flash.h b/src/drivers/boards/px4cannode-v1/bootloader/src/flash.h
index db5f5827b..39af66942 100644
--- a/src/drivers/boards/px4cannode-v1/bootloader/src/flash.h
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/flash.h
@@ -75,7 +75,7 @@ typedef enum {
* address - The word aligned address of the flash to erase
*
* Returned value:
- * On sucess FLASH_OK On Error one of the flash_error_t
+ * On success FLASH_OK On Error one of the flash_error_t
*
****************************************************************************/
@@ -93,7 +93,7 @@ flash_error_t bl_flash_erase(size_t address);
* to the flash.
*
* Returned value:
- * On sucess FLASH_OK On Error one of the flash_error_t
+ * On success FLASH_OK On Error one of the flash_error_t
*
****************************************************************************/
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/timer.c b/src/drivers/boards/px4cannode-v1/bootloader/src/timer.c
index 6f2014063..a88306b1f 100644
--- a/src/drivers/boards/px4cannode-v1/bootloader/src/timer.c
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/timer.c
@@ -1,22 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2015 PX4 Development Team. All rights reserved.
+ * Author: Ben Dyer <ben_dyer@mac.com>
+ * Pavel Kirienko <pavel.kirienko@zubax.com>
+ * David Sidrane <david_s5@nscdg.com>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
#include <nuttx/config.h>
#include "board_config.h"
+#include <systemlib/visibility.h>
+
#include <sys/types.h>
#include <stdint.h>
#include <string.h>
#include <nuttx/arch.h>
#include <arch/irq.h>
+#include <arch/board/board.h>
#include "bl_macros.h"
#include "timer.h"
#include "nvic.h"
-#include <arch/board/board.h>
-
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
typedef enum {
OneShot = modeOneShot,
@@ -36,64 +82,183 @@ typedef struct {
bl_timer_ctl_t ctl;
} bl_timer_t;
-bl_timer_t timers[OPT_BL_NUMBER_TIMERS];
-
-bl_timer_cb_t null_cb =
- {
- 0,
- 0
- };
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
static time_ms_t sys_tic;
+static bl_timer_t timers[OPT_BL_NUMBER_TIMERS];
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* Use to initialize */
+
+const bl_timer_cb_t null_cb = { 0, 0 };
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: timer_tic
+ *
+ * Description:
+ * Returns the system tic counter that counts in units of
+ * (CONFIG_USEC_PER_TICK/1000). By default 10 Ms.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
time_ms_t timer_tic(void)
{
return sys_tic;
}
+/****************************************************************************
+ * Name: sched_process_timer
+ *
+ * Description:
+ * Called by Nuttx on the ISR of the SysTic. This function run the list of
+ * timers. It deducts that amount of the time of a system tick from the
+ * any timers that are in use and running.
+ *
+ * Depending on the mode of the timer, the appropriate actions is taken on
+ * expiration.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
void sched_process_timer(void)
{
PROBE(1,true);
PROBE(1,false);
+ /* Increment the per-tick system counter */
+
sys_tic++;
+
+
+ /* todo:May need a X tick here is threads run long */
+
time_ms_t ms_elapsed = (CONFIG_USEC_PER_TICK/1000);
+
+ /* Walk the time list from High to low and */
+
bl_timer_id t;
for( t = arraySize(timers)-1; (int8_t) t >= 0; t--) {
+
+
+ /* Timer in use and running */
+
if ((timers[t].ctl & (inuse|running)) == (inuse|running)) {
+
+ /* Is it NOT already expired nor about to expire ?*/
+
if (timers[t].count != 0 && timers[t].count > ms_elapsed) {
+
+ /* So just remove the amount attributed to the tick */
+
timers[t].count -= ms_elapsed;
+
} else {
- timers[t].count = 0;
-
- switch(timers[t].ctl & ~(inuse|running)) {
-
- case Timeout:
- break;
- case OneShot: {
- bl_timer_cb_t user = timers[t].usr;
- memset(&timers[t], 0, sizeof(timers[t]));
- if (user.cb) {
- user.cb(t, user.context);
- }
- }
- break;
- case Repeating:
- timers[t].count = timers[t].reload;
- if (timers[t].usr.cb) {
- timers[t].usr.cb(t, timers[t].usr.context);
- }
- break;
- default:
- break;
- }
+
+ /* it has expired now or less than a tick ago */
+
+ /* Mark it expired */
+
+ timers[t].count = 0;
+
+ /* Now perform action based on mode */
+
+ switch(timers[t].ctl & ~(inuse|running)) {
+
+ case OneShot: {
+ bl_timer_cb_t user = timers[t].usr;
+ memset(&timers[t], 0, sizeof(timers[t]));
+ if (user.cb) {
+ user.cb(t, user.context);
+ }
+ }
+ break;
+ case Repeating:
+ case Timeout:
+ timers[t].count = timers[t].reload;
+ if (timers[t].usr.cb) {
+ timers[t].usr.cb(t, timers[t].usr.context);
+ }
+ break;
+ default:
+ break;
}
}
}
+ }
}
-bl_timer_id timer_allocate(bl_timer_modes_t mode, time_ms_t msfromnow, bl_timer_cb_t *fc)
+/****************************************************************************
+ * Name: timer_allocate
+ *
+ * Description:
+ * Is used to allocate a timer. Allocation does not involve memory
+ * allocation as the data for the timer are compile time generated.
+ * See OPT_BL_NUMBER_TIMERS
+ *
+ * There is an inherent priority to the timers in that the first timer
+ * allocated is the first timer run per tick.
+ *
+ * There are 3 modes of operation for the timers. All modes support an
+ * optional call back on expiration.
+ *
+ * modeOneShot - Specifies a one-shot timer. After notification timer
+ * is resource is freed.
+ * modeRepeating - Specifies a repeating timer that will reload and
+ * call an optional.
+ * modeTimeout - Specifies a persistent start / stop timer.
+ *
+ * modeStarted - Or'ed in to start the timer when allocated
+ *
+ *
+ * Input Parameters:
+ * mode - One of bl_timer_modes_t with the Optional modeStarted
+ * msfromnow - The reload and initial value for the timer in Ms.
+ * fc - A pointer or NULL (0). If it is non null it can be any
+ * of the following:
+ *
+ * a) A bl_timer_cb_t populated on the users stack or
+ * in the data segment. The values are copied into the
+ * internal data structure of the timer and therefore do
+ * not have to persist after the call to timer_allocate
+ *
+ * b) The address of null_cb. This is identical to passing
+ * null for the value of fc.
+ *
+ * Returned Value:
+ * On success a value from 0 - OPT_BL_NUMBER_TIMERS-1 that is
+ * the bl_timer_id for subsequent timer operations
+ * -1 on failure. This indicates there are no free timers.
+ *
+ ****************************************************************************/
+bl_timer_id timer_allocate(bl_timer_modes_t mode, time_ms_t msfromnow,
+ bl_timer_cb_t *fc)
{
bl_timer_id t;
irqstate_t s = irqsave();
@@ -115,6 +280,22 @@ bl_timer_id timer_allocate(bl_timer_modes_t mode, time_ms_t msfromnow, bl_timer_
}
+/****************************************************************************
+ * Name: timer_free
+ *
+ * Description:
+ * Is used to free a timer. Freeing a timer does not involve memory
+ * deallocation as the data for the timer are compile time generated.
+ * See OPT_BL_NUMBER_TIMERS
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
void timer_free(bl_timer_id id)
{
DEBUGASSERT(id>=0 && id < arraySize(timers));
@@ -123,6 +304,21 @@ void timer_free(bl_timer_id id)
irqrestore(s);
}
+/****************************************************************************
+ * Name: timer_start
+ *
+ * Description:
+ * Is used to Start a timer. The reload value is copied to the counter.
+ * And the running bit it set. There is no problem in Starting a running
+ * timer. But it will restart the timeout.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
void timer_start(bl_timer_id id)
{
DEBUGASSERT(id>=0 && id < arraySize(timers) && (timers[id].ctl & inuse));
@@ -132,6 +328,21 @@ void timer_start(bl_timer_id id)
irqrestore(s);
}
+
+/****************************************************************************
+ * Name: timer_stop
+ *
+ * Description:
+ * Is used to stop a timer. It is Ok to stop a stopped timer.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
void timer_stop(bl_timer_id id)
{
DEBUGASSERT(id>=0 && id < arraySize(timers) && (timers[id].ctl & inuse));
@@ -141,6 +352,21 @@ void timer_stop(bl_timer_id id)
}
+/****************************************************************************
+ * Name: timer_expired
+ *
+ * Description:
+ * Test if a timer that was configured as a modeTimeout timer is expired.
+ * To be expired the time has to be running and have a count of 0.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * No Zero if the timer is expired otherwise zero.
+ *
+ ****************************************************************************/
+
int timer_expired(bl_timer_id id)
{
DEBUGASSERT(id>=0 && id < arraySize(timers) && (timers[id].ctl & inuse));
@@ -150,11 +376,22 @@ int timer_expired(bl_timer_id id)
return rv;
}
-time_ref_t timer_ref(bl_timer_id id)
-{
- DEBUGASSERT(id>=0 && id < arraySize(timers) && (timers[id].ctl & inuse));
- return (time_ref_t) &timers[id].count;
-}
+/****************************************************************************
+ * Name: timer_restart
+ *
+ * Description:
+ * Is used to re start a timer with a new reload count. The reload value
+ * is copied to the counter and the running bit it set. There is no
+ * problem in restarting a running timer.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ * ms - Is a time_ms_t and the new reload value to use.
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
void timer_restart(bl_timer_id id, time_ms_t ms)
{
@@ -165,19 +402,68 @@ void timer_restart(bl_timer_id id, time_ms_t ms)
irqrestore(s);
}
-__attribute__ ((visibility ("default")))
+/****************************************************************************
+ * Name: timer_ref
+ *
+ * Description:
+ * Returns an time_ref_t that is a reference (ponter) to the internal counter
+ * of the timer selected by id. It should only be used with calls to
+ * timer_ref_expired.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * An internal reference that should be treated as opaque by the caller and
+ * should only be used with calls to timer_ref_expired.
+ * There is no reference counting on the reference and therefore does not
+ * require any operation to free it.
+ *
+ *************************************************************************/
+
+time_ref_t timer_ref(bl_timer_id id)
+{
+ DEBUGASSERT(id>=0 && id < arraySize(timers) && (timers[id].ctl & inuse));
+ return (time_ref_t) &timers[id].count;
+}
+
+/****************************************************************************
+ * Name: timer_init
+ *
+ * Description:
+ * Called early in os_start to initialize the data associated with
+ * the timers
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+__EXPORT
void timer_init(void)
{
-/* PROBE_INIT(7);
+ /* For system timing probing see bord.h and
+ * CONFIG_BOARD_USE_PROBES
+ */
+ PROBE_INIT(7);
PROBE(1,true);
PROBE(2,true);
PROBE(3,true);
PROBE(1,false);
PROBE(2,false);
PROBE(3,false);
-// *((uint32_t *)0x40011010) = 0x100; // PROBE(3,true);
-// *((uint32_t *)0x40011014) = 0x100; // PROBE(3,false);
-*/
+ /* This is the lowlevel IO if needed to instrument timing
+ * with the smallest impact
+ * *((uint32_t *)0x40011010) = 0x100; // PROBE(3,true);
+ * *((uint32_t *)0x40011014) = 0x100; // PROBE(3,false);
+ */
+
+ /* Initialize timer data */
+
+ sys_tic= 0;
memset(timers,0,sizeof(timers));
}
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/timer.h b/src/drivers/boards/px4cannode-v1/bootloader/src/timer.h
index 65f977d3b..7f125c702 100644
--- a/src/drivers/boards/px4cannode-v1/bootloader/src/timer.h
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/timer.h
@@ -33,9 +33,15 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
-
#pragma once
+/*
+ * We support two classes of timer interfaces. The first one is for structured
+ * timers that have an API for life cycle management and use. (timer_xx)
+ * The Second type of methods are for interfacing to a high resolution
+ * counter with fast access and are provided via an in line API (timer_hrt)
+ */
+
/****************************************************************************
* Included Files
****************************************************************************/
@@ -54,28 +60,55 @@
* Public Type Definitions
****************************************************************************/
+/* Types for timer access */
+typedef uint8_t bl_timer_id; /* A timer handle */
+typedef uint32_t time_ms_t; /* A timer value */
+typedef volatile time_ms_t* time_ref_t; /* A pointer to the internal
+ counter in the structure of a timer
+ used to do a time out test value */
+
+typedef uint32_t time_hrt_cycles_t; /* A timer value type of the hrt */
+
+
+/*
+ * Timers
+ *
+ * There are 3 modes of operation for the timers.
+ * All modes support a call back on expiration.
+ *
+ */
typedef enum {
- //! Specifies a one-shot timer. After notification timer is discarded.
+ /* Specifies a one-shot timer. After notification timer is discarded. */
modeOneShot = 1,
- //! Specifies a repeating timer.
+ /* Specifies a repeating timer. */
modeRepeating = 2,
- //! Specifies a persisten start / stop timer.
+ /* Specifies a persistent start / stop timer. */
modeTimeout = 3,
-
+ /* Or'ed in to start the timer when allocated */
modeStarted = 0x40
-
-
} bl_timer_modes_t;
-typedef uint8_t bl_timer_id;
-typedef uint32_t time_ms_t;
-typedef volatile time_ms_t* time_ref_t;
-
-typedef uint32_t time_hrt_cycles_t;
+/* The call back function signature type */
typedef void (*bl_timer_ontimeout)(bl_timer_id id, void *context);
+/*
+ * A helper type for timer allocation to setup a callback
+ * There is a null_cb object (see below) that can be used to
+ * a bl_timer_cb_t.
+ *
+ * Typical usage is:
+ *
+ * void my_process(bl_timer_id id, void *context) {
+ * ...
+ * };
+ *
+ * bl_timer_cb_t mycallback = null_cb;
+ * mycallback.cb = my_process;
+ * bl_timer_id mytimer = timer_allocate(modeRepeating|modeStarted, 100, &mycallback);
+ */
+
typedef struct {
void *context;
bl_timer_ontimeout cb;
@@ -87,39 +120,279 @@ typedef struct {
* Global Variables
****************************************************************************/
-extern bl_timer_cb_t null_cb;
+extern const bl_timer_cb_t null_cb;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
+/****************************************************************************
+ * Name: timer_init
+ *
+ * Description:
+ * Called early in os_start to initialize the data associated with
+ * the timers
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
void timer_init(void);
-bl_timer_id timer_allocate(bl_timer_modes_t mode, time_ms_t msfromnow, bl_timer_cb_t *fc);
+
+/****************************************************************************
+ * Name: timer_allocate
+ *
+ * Description:
+ * Is used to allocate a timer. Allocation does not involve memory
+ * allocation as the data for the timer are compile time generated.
+ * See OPT_BL_NUMBER_TIMERS
+ *
+ * There is an inherent priority to the timers in that the first timer
+ * allocated is the first timer run per tick.
+ *
+ * There are 3 modes of operation for the timers. All modes support an
+ * optional call back on expiration.
+ *
+ * modeOneShot - Specifies a one-shot timer. After notification timer
+ * is resource is freed.
+ * modeRepeating - Specifies a repeating timer that will reload and
+ * call an optional.
+ * modeTimeout - Specifies a persistent start / stop timer.
+ *
+ * modeStarted - Or'ed in to start the timer when allocated
+ *
+ *
+ * Input Parameters:
+ * mode - One of bl_timer_modes_t with the Optional modeStarted
+ * msfromnow - The reload and initial value for the timer in Ms.
+ * fc - A pointer or NULL (0). If it is non null it can be any
+ * of the following:
+ *
+ * a) A bl_timer_cb_t populated on the users stack or
+ * in the data segment. The values are copied into the
+ * internal data structure of the timer and therefore do
+ * not have to persist after the call to timer_allocate
+ *
+ * b) The address of null_cb. This is identical to passing
+ * null for the value of fc.
+ *
+ * Returned Value:
+ * On success a value from 0 - OPT_BL_NUMBER_TIMERS-1 that is
+ * the bl_timer_id for subsequent timer operations
+ * -1 on failure. This indicates there are no free timers.
+ *
+ ****************************************************************************/
+
+bl_timer_id timer_allocate(bl_timer_modes_t mode, time_ms_t msfromnow,
+ bl_timer_cb_t *fc);
+
+/****************************************************************************
+ * Name: timer_free
+ *
+ * Description:
+ * Is used to free a timer. Freeing a timer does not involve memory
+ * deallocation as the data for the timer are compile time generated.
+ * See OPT_BL_NUMBER_TIMERS
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
void timer_free(bl_timer_id id);
+
+/****************************************************************************
+ * Name: timer_start
+ *
+ * Description:
+ * Is used to Start a timer. The reload value is copied to the counter.
+ * And the running bit it set. There is no problem in Starting a running
+ * timer. But it will restart the timeout.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
void timer_start(bl_timer_id id);
+
+/****************************************************************************
+ * Name: timer_restart
+ *
+ * Description:
+ * Is used to re start a timer with a new reload count. The reload value
+ * is copied to the counter and the running bit it set. There is no
+ * problem in restarting a running timer.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ * ms - Is a time_ms_t and the new reload value to use.
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
void timer_restart(bl_timer_id id, time_ms_t ms);
+
+/****************************************************************************
+ * Name: timer_stop
+ *
+ * Description:
+ * Is used to stop a timer. It is Ok to stop a stopped timer.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
void timer_stop(bl_timer_id id);
+
+/****************************************************************************
+ * Name: timer_expired
+ *
+ * Description:
+ * Test if a timer that was configured as a modeTimeout timer is expired.
+ * To be expired the time has to be running and have a count of 0.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * No Zero if the timer is expired otherwise zero.
+ *
+ ****************************************************************************/
+
int timer_expired(bl_timer_id id);
-time_ms_t timer_tic(void);
+
+/****************************************************************************
+ * Name: timer_ref
+ *
+ * Description:
+ * Returns an time_ref_t that is a reference (pointer) to the internal counter
+ * of the timer selected by id. It should only be used with calls to
+ * timer_ref_expired.
+ *
+ * Input Parameters:
+ * id - Returned from timer_allocate;
+ *
+ * Returned Value:
+ * An internal reference that should be treated as opaque by the caller and
+ * should only be used with calls to timer_ref_expired.
+ * There is no reference counting on the reference and therefore does not
+ * require any operation to free it.
+ *
+ ****************************************************************************/
time_ref_t timer_ref(bl_timer_id id);
+
+/****************************************************************************
+ * Name: timer_ref_expired
+ *
+ * Description:
+ * Test if a timer, that was configured as a modeTimeout timer is expired
+ * based on the reference provided.
+ *
+ * Input Parameters:
+ * ref - Returned timer_ref;
+ *
+ * Returned Value:
+ * No Zero if the timer is expired otherwise zero.
+ *
+ ****************************************************************************/
+
static inline int timer_ref_expired(time_ref_t ref)
{
return *ref == 0;
}
+/****************************************************************************
+ * Name: timer_tic
+ *
+ * Description:
+ * Returns the system tic counter that counts in units of
+ * (CONFIG_USEC_PER_TICK/1000). By default 10 Ms.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+time_ms_t timer_tic(void);
+
+
+/****************************************************************************
+ * Name: timer_hrt_read
+ *
+ * Description:
+ * Returns the hardware SysTic counter that counts in units of
+ * STM32_HCLK_FREQUENCY. This file defines TIMER_HRT_CYCLES_PER_US
+ * and TIMER_HRT_CYCLES_PER_MS that should be used to define times.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * The current value of the HW counter in the type of time_hrt_cycles_t.
+ *
+ ****************************************************************************/
static inline time_hrt_cycles_t timer_hrt_read(void)
{
return getreg32(NVIC_SYSTICK_CURRENT);
}
+/****************************************************************************
+ * Name: timer_hrt_max
+ *
+ * Description:
+ * Returns the hardware SysTic reload value +1
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * The current SysTic reload of the HW counter in the type of
+ * time_hrt_cycles_t.
+ *
+ ****************************************************************************/
+
static inline time_hrt_cycles_t timer_hrt_max(void)
{
return getreg32(NVIC_SYSTICK_RELOAD) + 1;
}
+/****************************************************************************
+ * Name: timer_hrt_elapsed
+ *
+ * Description:
+ * Returns the difference between 2 time values, taking into account
+ * the way the timer wrap.
+ *
+ * Input Parameters:
+ * begin - Beginning timer count.
+ * end - Ending timer count.
+ *
+ * Returned Value:
+ * The difference from begin to end
+ *
+ ****************************************************************************/
+
static inline time_hrt_cycles_t timer_hrt_elapsed(time_hrt_cycles_t begin, time_hrt_cycles_t end)
{
/* It is a down count from NVIC_SYSTICK_RELOAD */