aboutsummaryrefslogtreecommitdiff
path: root/nuttx/configs/px4io/include
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/px4io/include')
-rwxr-xr-xnuttx/configs/px4io/include/README.txt1
-rwxr-xr-xnuttx/configs/px4io/include/board.h167
-rw-r--r--nuttx/configs/px4io/include/drv_gpio.h67
-rw-r--r--nuttx/configs/px4io/include/drv_i2c_device.h42
-rw-r--r--nuttx/configs/px4io/include/drv_ppm_input.h100
-rw-r--r--nuttx/configs/px4io/include/drv_pwm_servo.h94
-rwxr-xr-xnuttx/configs/px4io/include/up_boardinitialize.h43
-rw-r--r--nuttx/configs/px4io/include/up_hrt.h129
8 files changed, 643 insertions, 0 deletions
diff --git a/nuttx/configs/px4io/include/README.txt b/nuttx/configs/px4io/include/README.txt
new file mode 100755
index 000000000..2264a80aa
--- /dev/null
+++ b/nuttx/configs/px4io/include/README.txt
@@ -0,0 +1 @@
+This directory contains header files unique to the PX4IO board.
diff --git a/nuttx/configs/px4io/include/board.h b/nuttx/configs/px4io/include/board.h
new file mode 100755
index 000000000..cd4d48649
--- /dev/null
+++ b/nuttx/configs/px4io/include/board.h
@@ -0,0 +1,167 @@
+/************************************************************************************
+ * configs/px4io/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Copyright (C) 2012 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 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+# include <stdbool.h>
+#endif
+#include "stm32_rcc.h"
+#include "stm32_sdio.h"
+#include "stm32_internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+
+/* On-board crystal frequency is 24MHz (HSE) */
+
+#define STM32_BOARD_XTAL 24000000ul
+
+/* Use the HSE output as the system clock */
+
+#define STM32_SYSCLK_SW RCC_CFGR_SW_HSE
+#define STM32_SYSCLK_SWS RCC_CFGR_SWS_HSE
+#define STM32_SYSCLK_FREQUENCY STM32_BOARD_XTAL
+
+/* AHB clock (HCLK) is SYSCLK (24MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB2 clock (PCLK2) is HCLK (24MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
+#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY
+#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-4 */
+
+/* APB2 timer 1 will receive PCLK2. */
+
+#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
+
+/* APB1 clock (PCLK1) is HCLK (24MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY)
+
+/* All timers run off PCLK */
+
+#define STM32_APB1_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB1_TIM2_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY)
+
+/*
+ * High-resolution timer
+ */
+#ifdef CONFIG_HRT_TIMER
+# define HRT_TIMER 1 /* use timer1 for the HRT */
+# define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
+#endif
+
+/*
+ * PPM
+ *
+ * PPM input is handled by the HRT timer.
+ *
+ * Pin is PA8, timer 1, channel 1
+ */
+#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM)
+# define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
+# define GPIO_PPM_IN GPIO_TIM1_CH1IN
+#endif
+
+/*
+ * PWM
+ *
+ * PWM configuration is provided via the configuration structure in up_boardinitialize.c
+ */
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+EXTERN void stm32_boardinitialize(void);
+
+/************************************************************************************
+ * Power switch support.
+ */
+extern void up_power_init(void);
+extern void up_power_set(int port, bool state);
+extern bool up_power_error(int port);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx/configs/px4io/include/drv_gpio.h b/nuttx/configs/px4io/include/drv_gpio.h
new file mode 100644
index 000000000..329d2bacf
--- /dev/null
+++ b/nuttx/configs/px4io/include/drv_gpio.h
@@ -0,0 +1,67 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 GPIO driver for PX4IO
+ */
+
+#include <sys/ioctl.h>
+
+#define _GPIO_IOCTL_BASE 0x7700
+
+#define GPIO_SET(_x) _IOC(_GPIO_IOCTL_BASE, _x)
+#define GPIO_GET(_x) _IOC(_GPIO_IOCTL_BASE + 1, _x)
+
+/*
+ * List of GPIOs; must be sorted with settable GPIOs first.
+ */
+#define GPIO_ACC1_POWER 0 /* settable */
+#define GPIO_ACC2_POWER 1
+#define GPIO_SERVO_POWER 2
+#define GPIO_RELAY1 3
+#define GPIO_RELAY2 4
+#define GPIO_LED_BLUE 5
+#define GPIO_LED_AMBER 6
+#define GPIO_LED_SAFETY 7
+
+#define GPIO_ACC_OVERCURRENT 8 /* readonly */
+#define GPIO_SERVO_OVERCURRENT 9
+#define GPIO_SAFETY_BUTTON 10
+
+#define GPIO_MAX_SETTABLE 7
+#define GPIO_MAX 10
+
+/*
+ * GPIO driver init function.
+ */
+extern int gpio_drv_init(void);
diff --git a/nuttx/configs/px4io/include/drv_i2c_device.h b/nuttx/configs/px4io/include/drv_i2c_device.h
new file mode 100644
index 000000000..02582bc09
--- /dev/null
+++ b/nuttx/configs/px4io/include/drv_i2c_device.h
@@ -0,0 +1,42 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 A simple, polled I2C slave-mode driver.
+ *
+ * The master writes to and reads from a byte buffer, which the caller
+ * can update inbetween calls to the FSM.
+ */
+
+extern void i2c_fsm_init(uint8_t *buffer, size_t buffer_size);
+extern bool i2c_fsm(void);
diff --git a/nuttx/configs/px4io/include/drv_ppm_input.h b/nuttx/configs/px4io/include/drv_ppm_input.h
new file mode 100644
index 000000000..78c424154
--- /dev/null
+++ b/nuttx/configs/px4io/include/drv_ppm_input.h
@@ -0,0 +1,100 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 PPM input decoder.
+ *
+ * Works in conjunction with the HRT driver, exports a device node
+ * and a message queue (if message queues are enabled).
+ *
+ * Note that the device node supports both blocking and non-blocking
+ * opens, but actually never blocks. A nonblocking open will return
+ * EWOULDBLOCK if there has not been an update since the last read,
+ * while a blocking open will always return the most recent data.
+ */
+
+#include <sys/ioctl.h>
+
+#define _PPM_INPUT_BASE 0x7600
+
+/*
+ * Fetch the state of the PPM input detector.
+ */
+#define PPM_INPUT_STATUS _IOC(_PPM_INPUT_BASE, 0)
+
+typedef enum {
+ PPM_STATUS_NO_SIGNAL = 0,
+ PPM_STATUS_SIGNAL_CURRENT = 1,
+} ppm_input_status_t;
+
+/*
+ * Fetch the number of channels decoded (only valid when PPM_STATUS_SIGNAL_CURRENT).
+ */
+#define PPM_INPUT_CHANNELS _IOC(_PPM_INPUT_BASE, 1)
+
+typedef int ppm_input_channel_count_t;
+
+/*
+ * Device node
+ */
+#define PPM_DEVICE_NODE "/dev/ppm_input"
+
+/*
+ * Message queue; if message queues are supported, PPM input data is
+ * supplied to the queue when a frame is decoded.
+ */
+#ifndef CONFIG_DISABLE_MQUEUE
+# define PPM_MESSAGE_QUEUE "ppm_input"
+#endif
+
+/*
+ * Private hook from the HRT driver to the PPM decoder.
+ *
+ * This function is called for every edge of the incoming PPM
+ * signal.
+ *
+ * @param reset If true, the decoder should be reset (e.g.)
+ * capture failure was detected.
+ * @param count The counter value at which the edge
+ * was captured.
+ */
+
+void ppm_input_decode(bool reset, uint16_t count);
+
+/*
+ * PPM input initialisation function.
+ *
+ * If message queues are enabled, and mq_name is not NULL, received input
+ * is posted to the message queue as an array of 16-bit unsigned channel values.
+ */
+int ppm_input_init(const char *mq_name); \ No newline at end of file
diff --git a/nuttx/configs/px4io/include/drv_pwm_servo.h b/nuttx/configs/px4io/include/drv_pwm_servo.h
new file mode 100644
index 000000000..663468404
--- /dev/null
+++ b/nuttx/configs/px4io/include/drv_pwm_servo.h
@@ -0,0 +1,94 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 PWM servo driver.
+ *
+ * The pwm_servo driver supports servos connected to STM32 timer
+ * blocks.
+ *
+ * Servo values can be set either with the PWM_SERVO_SET ioctl, or
+ * by writing an array of servo_position_t values to the device.
+ * Writing a value of 0 to a channel suppresses any output for that
+ * channel.
+ *
+ * Servo values can be read back either with the PWM_SERVO_GET
+ * ioctl, or by reading an array of servo_position_t values
+ * from the device.
+ *
+ * Attempts to set a channel that is not configured are ignored,
+ * and unconfigured channels always read zero.
+ *
+ * The PWM_SERVO_ARM / PWM_SERVO_DISARM calls globally arm
+ * (enable) and disarm (disable) all servo outputs.
+ */
+
+#include <sys/ioctl.h>
+
+#define _PWM_SERVO_BASE 0x7500
+#define PWM_SERVO_ARM _IOC(_PWM_SERVO_BASE, 0)
+#define PWM_SERVO_DISARM _IOC(_PWM_SERVO_BASE, 1)
+
+#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)
+#define PWM_SERVO_GET(_servo) _IOC(_PWM_SERVO_BASE, 0x40 + _servo)
+
+typedef uint16_t servo_position_t;
+
+/* configuration limits */
+#define PWM_SERVO_MAX_TIMERS 3
+#define PWM_SERVO_MAX_CHANNELS 8
+
+struct pwm_servo_config {
+ /* rate (in Hz) of PWM updates */
+ uint32_t update_rate;
+
+ /* array of timers dedicated to PWM servo use */
+ struct pwm_servo_timer {
+ uint32_t base;
+ uint32_t clock_register;
+ uint32_t clock_bit;
+ uint32_t clock_freq;
+ } timers[PWM_SERVO_MAX_TIMERS];
+
+ /* array of channels in logical order */
+ struct pwm_servo_channel {
+ uint32_t gpio;
+ uint8_t timer_index;
+ uint8_t timer_channel;
+ servo_position_t default_value;
+ } channels[PWM_SERVO_MAX_CHANNELS];
+};
+
+extern int pwm_servo_init(const struct pwm_servo_config *config);
+
+
diff --git a/nuttx/configs/px4io/include/up_boardinitialize.h b/nuttx/configs/px4io/include/up_boardinitialize.h
new file mode 100755
index 000000000..01b9ca214
--- /dev/null
+++ b/nuttx/configs/px4io/include/up_boardinitialize.h
@@ -0,0 +1,43 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 Board initialisation prototype(s)
+ */
+
+#ifndef __UP_BOARDINITIALIZE_H
+#define __UP_BOARDINITIALIZE_H
+
+extern int up_boardinitialize(void);
+
+#endif
diff --git a/nuttx/configs/px4io/include/up_hrt.h b/nuttx/configs/px4io/include/up_hrt.h
new file mode 100644
index 000000000..c83f14ac3
--- /dev/null
+++ b/nuttx/configs/px4io/include/up_hrt.h
@@ -0,0 +1,129 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 High-resolution timer callouts and timekeeping.
+ */
+
+#ifndef UP_HRT_H_
+#define UP_HRT_H_
+
+#include <sys/types.h>
+#include <stdbool.h>
+
+#include <time.h>
+#include <queue.h>
+
+/*
+ * Absolute time, in microsecond units.
+ *
+ * Absolute time is measured from some arbitrary epoch shortly after
+ * system startup. It should never wrap or go backwards.
+ */
+typedef uint64_t hrt_abstime;
+
+/*
+ * Callout function type.
+ *
+ * Note that callouts run in the timer interrupt context, so
+ * they are serialised with respect to each other, and must not
+ * block.
+ */
+typedef void (* hrt_callout)(void *arg);
+
+/*
+ * Callout record.
+ */
+struct hrt_call {
+ struct sq_entry_s link;
+
+ hrt_abstime deadline;
+ hrt_abstime period;
+ hrt_callout callout;
+ void *arg;
+};
+
+/*
+ * Get absolute time.
+ */
+extern hrt_abstime hrt_absolute_time(void);
+
+/*
+ * Convert a timespec to absolute time.
+ */
+extern hrt_abstime ts_to_abstime(struct timespec *ts);
+
+/*
+ * Convert absolute time to a timespec.
+ */
+extern void abstime_to_ts(struct timespec *ts, hrt_abstime abstime);
+
+/*
+ * Call callout(arg) after delay has elapsed.
+ *
+ * If callout is NULL, this can be used to implement a timeout by testing the call
+ * with hrt_called().
+ */
+extern void hrt_call_after(struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, void *arg);
+
+/*
+ * Call callout(arg) at absolute time calltime.
+ */
+extern void hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, void *arg);
+
+/*
+ * Call callout(arg) after delay, and then after every interval.
+ *
+ * Note thet the interval is timed between scheduled, not actual, call times, so the call rate may
+ * jitter but should not drift.
+ */
+extern void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg);
+
+/*
+ * If this returns true, the entry has been invoked and removed from the callout list.
+ *
+ * Always returns false for repeating callouts.
+ */
+extern bool hrt_called(struct hrt_call *entry);
+
+/*
+ * Remove the entry from the callout list.
+ */
+extern void hrt_cancel(struct hrt_call *entry);
+
+/*
+ * Initialise the HRT.
+ */
+extern void hrt_init(int timer);
+
+#endif /* UP_HRT_H_ */