aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorJakob Odersky <jodersky@gmail.com>2015-05-11 19:31:38 +0200
committerJakob Odersky <jodersky@gmail.com>2015-05-14 12:27:10 +0200
commitdb9ebbb5fa795713805497f3b70fcccf874ec4d5 (patch)
tree0522bf2e69f82aad2e96b05908d0995402d7a4f0
parent893d4160e93f47e333b79e380fed88c9d9e7b732 (diff)
downloadpx4-firmware-db9ebbb5fa795713805497f3b70fcccf874ec4d5.tar.gz
px4-firmware-db9ebbb5fa795713805497f3b70fcccf874ec4d5.tar.bz2
px4-firmware-db9ebbb5fa795713805497f3b70fcccf874ec4d5.zip
implement basic driver, c++ and pwm
m---------NuttX0
-rw-r--r--makefiles/config_trifle_default.mk5
-rw-r--r--nuttx-configs/trifle/nsh/defconfig43
-rw-r--r--src/drivers/boards/trifle/devconfig.c27
-rw-r--r--src/drivers/boards/trifle/module.mk2
-rw-r--r--src/drivers/device/module.mk8
-rw-r--r--src/drivers/kinetis/drv_pwm_servo.c226
-rw-r--r--src/drivers/kinetis/drv_pwm_servo.h90
-rw-r--r--src/drivers/kinetis/module.mk3
-rw-r--r--src/drivers/kinetis/up_cxxinitialize.c147
-rw-r--r--src/examples/pwm/module.mk3
-rw-r--r--src/examples/pwm/pwm.c18
-rw-r--r--src/modules/helloworld/helloworld.c10
-rw-r--r--src/modules/helloworld/module.mk3
14 files changed, 549 insertions, 36 deletions
diff --git a/NuttX b/NuttX
-Subproject f573c78fc173cfba41f00958230d141e7136e62
+Subproject 9c9892196b2498615dc1c537f047cc6e56653d4
diff --git a/makefiles/config_trifle_default.mk b/makefiles/config_trifle_default.mk
index 471c210d5..339a7bdec 100644
--- a/makefiles/config_trifle_default.mk
+++ b/makefiles/config_trifle_default.mk
@@ -11,8 +11,9 @@ ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_trifle
# Board support modules
#
MODULES += drivers/boards/trifle
-MODULES += modules/helloworld
-#MODULES += drivers/device
+MODULES += examples/pwm
+MODULES += drivers/device
+MODULES += drivers/kinetis
#MODULES += drivers/stm32
#MODULES += drivers/stm32/adc
#MODULES += drivers/stm32/tone_alarm
diff --git a/nuttx-configs/trifle/nsh/defconfig b/nuttx-configs/trifle/nsh/defconfig
index f46649cfb..ba6a02b5b 100644
--- a/nuttx-configs/trifle/nsh/defconfig
+++ b/nuttx-configs/trifle/nsh/defconfig
@@ -16,6 +16,7 @@ CONFIG_HOST_LINUX=y
#
# Build Configuration
#
+CONFIG_APPS_DIR="../apps"
# CONFIG_BUILD_2PASS is not set
#
@@ -30,7 +31,7 @@ CONFIG_RAW_BINARY=y
# Customize Header Files
#
# CONFIG_ARCH_STDBOOL_H is not set
-# CONFIG_ARCH_MATH_H is not set
+CONFIG_ARCH_MATH_H=y
# CONFIG_ARCH_FLOAT_H is not set
# CONFIG_ARCH_STDARG_H is not set
@@ -129,19 +130,19 @@ CONFIG_KINETIS_UART0=y
CONFIG_KINETIS_SPI0=y
# CONFIG_KINETIS_SPI1 is not set
# CONFIG_KINETIS_SPI2 is not set
-# CONFIG_KINETIS_I2C0 is not set
+CONFIG_KINETIS_I2C0=y
# CONFIG_KINETIS_I2C1 is not set
# CONFIG_KINETIS_I2S is not set
-CONFIG_KINETIS_DAC0=y
+# CONFIG_KINETIS_DAC0 is not set
# CONFIG_KINETIS_DAC1 is not set
CONFIG_KINETIS_ADC0=y
# CONFIG_KINETIS_ADC1 is not set
# CONFIG_KINETIS_CMP is not set
# CONFIG_KINETIS_VREF is not set
# CONFIG_KINETIS_SDHC is not set
-# CONFIG_KINETIS_FTM0 is not set
-# CONFIG_KINETIS_FTM1 is not set
-# CONFIG_KINETIS_FTM2 is not set
+CONFIG_KINETIS_FTM0=y
+CONFIG_KINETIS_FTM1=y
+CONFIG_KINETIS_FTM2=y
# CONFIG_KINETIS_LPTIMER is not set
# CONFIG_KINETIS_RTC is not set
# CONFIG_KINETIS_EWM is not set
@@ -245,7 +246,7 @@ CONFIG_DEV_CONSOLE=y
# CONFIG_FDCLONE_DISABLE is not set
# CONFIG_FDCLONE_STDIO is not set
CONFIG_SDCLONE_DISABLE=y
-# CONFIG_SCHED_WAITPID is not set
+CONFIG_SCHED_WAITPID=y
# CONFIG_SCHED_STARTHOOK is not set
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_ATEXIT_MAX=1
@@ -293,14 +294,19 @@ CONFIG_PTHREAD_STACK_DEFAULT=2048
#
# Device Drivers
#
-CONFIG_DISABLE_POLL=y
+# CONFIG_DISABLE_POLL is not set
CONFIG_DEV_NULL=y
# CONFIG_DEV_ZERO is not set
# CONFIG_LOOP is not set
# CONFIG_RAMDISK is not set
# CONFIG_CAN is not set
# CONFIG_PWM is not set
-# CONFIG_I2C is not set
+CONFIG_I2C=y
+# CONFIG_I2C_SLAVE is not set
+CONFIG_I2C_TRANSFER=y
+# CONFIG_I2C_WRITEREAD is not set
+# CONFIG_I2C_POLLED is not set
+# CONFIG_I2C_TRACE is not set
# CONFIG_SPI is not set
# CONFIG_RTC is not set
# CONFIG_WATCHDOG is not set
@@ -321,6 +327,7 @@ CONFIG_SERIAL=y
CONFIG_ARCH_HAVE_UART0=y
CONFIG_MCU_SERIAL=y
CONFIG_STANDARD_SERIAL=y
+CONFIG_SERIAL_NPOLLWAITERS=2
CONFIG_UART0_SERIAL_CONSOLE=y
# CONFIG_NO_SERIAL_CONSOLE is not set
@@ -419,7 +426,6 @@ CONFIG_BUILTIN=y
CONFIG_STDIO_BUFFER_SIZE=64
CONFIG_STDIO_LINEBUFFER=y
CONFIG_NUNGET_CHARS=2
-CONFIG_LIBM=y
# CONFIG_NOPRINTF_FIELDWIDTH is not set
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIB_RAND_ORDER=1
@@ -448,8 +454,15 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
#
# Basic CXX Support
#
-# CONFIG_C99_BOOL8 is not set
-# CONFIG_HAVE_CXX is not set
+CONFIG_C99_BOOL8=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
#
# Application Configuration
@@ -466,6 +479,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
# CONFIG_EXAMPLES_BUTTONS is not set
# CONFIG_EXAMPLES_CAN is not set
# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_CXXTEST is not set
# CONFIG_EXAMPLES_DHCPD is not set
# CONFIG_EXAMPLES_ELF is not set
# CONFIG_EXAMPLES_FTPC is not set
@@ -644,6 +658,7 @@ CONFIG_NSH_CONSOLE=y
#
# I2C tool
#
+# CONFIG_SYSTEM_I2CTOOL is not set
#
# FLASH Program Installation
@@ -683,7 +698,3 @@ CONFIG_SYSTEM_SYSINFO=y
#
# USB Monitor
#
-
-# Application configuration
-
-CONFIG_APPS_DIR="../apps"
diff --git a/src/drivers/boards/trifle/devconfig.c b/src/drivers/boards/trifle/devconfig.c
new file mode 100644
index 000000000..47b69a27e
--- /dev/null
+++ b/src/drivers/boards/trifle/devconfig.c
@@ -0,0 +1,27 @@
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <errno.h>
+#include <chip.h>
+#include <kinetis_ftm.h>
+#include <kinetis_internal.h>
+#include <up_arch.h>
+#include <kinetis_sim.h>
+
+#include <drivers/kinetis/drv_pwm_servo.h>
+
+
+__EXPORT const struct pwm_servo_timer pwm_servo_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .ftm_base = KINETIS_FTM0_BASE,
+ .scgc = KINETIS_SIM_SCGC6,
+ .scgc_enable = 1 << 24
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_servo_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .timer = &pwm_servo_timers[0],
+ .ftm_channel = 5,
+ .pinconfig = PIN_PORTD | PIN5 | PIN_ALT4_OUTPUT | PIN_ALT4_HIGHDRIVE
+ }
+};
diff --git a/src/drivers/boards/trifle/module.mk b/src/drivers/boards/trifle/module.mk
index 1baa35ed0..7c4e4a525 100644
--- a/src/drivers/boards/trifle/module.mk
+++ b/src/drivers/boards/trifle/module.mk
@@ -2,6 +2,6 @@
# Board-specific startup code for the CONDOR
#
-SRCS = cfmconfig.c up_boot.c up_leds.c
+SRCS = cfmconfig.c devconfig.c up_boot.c up_leds.c
MAXOPTIMIZATION = -Os
diff --git a/src/drivers/device/module.mk b/src/drivers/device/module.mk
index 8c716d9cd..9b907394f 100644
--- a/src/drivers/device/module.mk
+++ b/src/drivers/device/module.mk
@@ -36,7 +36,7 @@
#
SRCS = cdev.cpp \
- device.cpp \
- i2c.cpp \
- pio.cpp \
- spi.cpp
+ device.cpp
+# i2c.cpp \
+# pio.cpp \
+# spi.cpp
diff --git a/src/drivers/kinetis/drv_pwm_servo.c b/src/drivers/kinetis/drv_pwm_servo.c
new file mode 100644
index 000000000..8a3d583ac
--- /dev/null
+++ b/src/drivers/kinetis/drv_pwm_servo.c
@@ -0,0 +1,226 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 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 drv_pwm_servo.c
+ *
+ * Servo driver supporting PWM servos connected to kinetis flex timer modules.
+ *
+ */
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <errno.h>
+#include <chip.h>
+#include <kinetis_ftm.h>
+#include <kinetis_internal.h>
+#include <up_arch.h>
+#include <kinetis_sim.h>
+
+#include "drv_pwm_servo.h"
+
+
+/**
+ * Intialise the PWM servo outputs using the specified configuration.
+ *
+ * @param channel_mask Bitmask of channels (LSB = channel 0) to enable.
+ * This allows some of the channels to remain configured
+ * as GPIOs or as another function.
+ * @return OK on success.
+ */
+ int
+ up_pwm_servo_init(uint32_t channel_mask)
+ {
+
+ for (size_t i = 0; i < PWM_SERVO_MAX_TIMERS; ++i) {
+
+ const struct pwm_servo_timer* timer = &pwm_servo_timers[i];
+ uint32_t regval;
+
+ regval = getreg32(timer->scgc);
+ putreg32(regval | timer->scgc_enable, timer->scgc); // enable clock signal
+ up_pwm_servo_set_rate_group_update(i, 50); // 50Hz default
+
+ }
+
+ for (size_t i = 0; i < PWM_SERVO_MAX_CHANNELS; ++i) {
+ const struct pwm_servo_channel* channel = &pwm_servo_channels[i];
+
+ if ((1 << i) & channel_mask) {
+ // enable edge aligned pwm
+ putreg32(0x28, channel->timer->ftm_base + KINETIS_FTM_CSC_OFFSET(channel->ftm_channel));
+ // configure pin
+ kinetis_pinconfig(channel->pinconfig);
+ }
+
+
+ }
+
+ return 0;
+ }
+
+/**
+ * De-initialise the PWM servo outputs.
+ */
+void
+up_pwm_servo_deinit(void)
+{
+
+}
+
+/**
+ * Arm or disarm servo outputs.
+ *
+ * When disarmed, servos output no pulse.
+ *
+ * @bug This function should, but does not, guarantee that any pulse
+ * currently in progress is cleanly completed.
+ *
+ * @param armed If true, outputs are armed; if false they
+ * are disarmed.
+ */
+void up_pwm_servo_arm(bool armed)
+{
+ for (size_t i = 0; i < PWM_SERVO_MAX_TIMERS; ++i) {
+ const struct pwm_servo_timer* timer = &pwm_servo_timers[i];
+
+ if (armed) {
+ putreg32(FTM_SC_CLKS_SYSCLK, timer->ftm_base + KINETIS_FTM_SC_OFFSET);
+ } else {
+ putreg32(FTM_SC_CLKS_NONE, timer->ftm_base + KINETIS_FTM_SC_OFFSET);
+ }
+
+ }
+}
+
+
+/**
+ * Set the servo update rate for all rate groups.
+ *
+ * @param rate The update rate in Hz to set.
+ * @return OK on success, -ERANGE if an unsupported update rate is set.
+ */
+int
+up_pwm_servo_set_rate(unsigned rate)
+{
+
+ return 0;
+}
+
+/**
+ * Get a bitmap of output channels assigned to a given rate group.
+ *
+ * @param group The rate group to query. Rate groups are assigned contiguously
+ * starting from zero.
+ * @return A bitmap of channels assigned to the rate group, or zero if
+ * the group number has no channels.
+ */
+uint32_t
+up_pwm_servo_get_rate_group(unsigned group)
+{
+ return 0;
+}
+
+/**
+ * Set the update rate for a given rate group.
+ *
+ * @param group The rate group whose update rate will be changed.
+ * @param rate The update rate in Hz.
+ * @return OK if the group was adjusted, -ERANGE if an unsupported update rate is set.
+ */
+int
+up_pwm_servo_set_rate_group_update(unsigned group, unsigned rate)
+{
+ const struct pwm_servo_timer* timer = &pwm_servo_timers[group];
+
+ putreg32(FTM_SC_PS_4, timer->ftm_base + KINETIS_FTM_SC_OFFSET);
+ putreg32(0, timer->ftm_base + KINETIS_FTM_CNT_OFFSET);
+ putreg32(48000, timer->ftm_base + KINETIS_FTM_MOD_OFFSET);
+
+ return 0;
+}
+
+/**
+ * Set the current output value for a channel.
+ *
+ * @param channel The channel to set.
+ * @param value The output pulse width in microseconds.
+ */
+int
+up_pwm_servo_set(unsigned channel, servo_position_t value)
+{
+ const struct pwm_servo_channel* ch = &pwm_servo_channels[channel];
+
+ putreg32(value * 48000 / 2000, ch->timer->ftm_base + KINETIS_FTM_CV_OFFSET(ch->ftm_channel));
+ return 0;
+}
+
+/**
+ * Get the current output value for a channel.
+ *
+ * @param channel The channel to read.
+ * @return The output pulse width in microseconds, or zero if
+ * outputs are not armed or not configured.
+ */
+servo_position_t
+up_pwm_servo_get(unsigned channel)
+{
+ return 0;
+}
+
+
+/*
+int helloworld_main(int args, char *argv[]) {
+ printf("Setting timer\n");
+
+ uint8_t ftm_channel = 5;
+ struct pwm_timer* timer = &pwm0;
+
+
+ uint32_t regval;
+ regval = getreg32(timer->scgc);
+ putreg32(regval | timer->scgc_enable, timer->scgc); // enable clock signal to FTM0
+
+ putreg32(0, timer->ftm_base + KINETIS_FTM_CNT_OFFSET);
+ putreg32(36864, timer->ftm_base + KINETIS_FTM_MOD_OFFSET);
+
+ putreg32(0x28, timer->ftm_base + KINETIS_FTM_CSC_OFFSET(ftm_channel)); // channle, enable edge aligned pwm
+
+ putreg32(FTM_SC_CLKS_SYSCLK | FTM_SC_PS_1, timer->ftm_base + KINETIS_FTM_SC_OFFSET); // set clock source of FTM module
+ putreg32(atoi(argv[1]), timer->ftm_base + KINETIS_FTM_CV_OFFSET(ftm_channel));
+
+ kinetis_pinconfig(PIN_PORTD | PIN5 | PIN_ALT4_OUTPUT | PIN_ALT4_HIGHDRIVE ) ;
+
+ printf("Done\n");
+ return 0;
+}
+*/
diff --git a/src/drivers/kinetis/drv_pwm_servo.h b/src/drivers/kinetis/drv_pwm_servo.h
new file mode 100644
index 000000000..160b7aad7
--- /dev/null
+++ b/src/drivers/kinetis/drv_pwm_servo.h
@@ -0,0 +1,90 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 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 drv_pwm_servo.h
+ *
+ * kinetis-specific PWM output data.
+ */
+#ifndef KINETIS_PWM_SERVO_H
+#define KINETIS_PWM_SERVO_H
+
+#define PWM_SERVO_MAX_TIMERS 1
+#define PWM_SERVO_MAX_CHANNELS 1
+
+#include <stdbool.h>
+#include <drivers/drv_pwm_output.h>
+
+/**
+ * Flex timer module dedicated to PWM servo use
+ *
+ */
+struct pwm_servo_timer {
+
+ /** Base memory address of timer module. */
+ uint32_t ftm_base;
+
+ /** Address of clock gating control register responsible
+ * for the given timer module. */
+ uint32_t scgc;
+
+ /** Bitmask to enable clock input to the timer module. */
+ uint32_t scgc_enable;
+
+};
+
+/**
+ * Logical servo output channel
+ */
+struct pwm_servo_channel {
+
+ /** Pointer to the underlying timer structure. */
+ const struct pwm_servo_timer* timer;
+
+ /** Channel number of the underlying flex module timer. */
+ uint8_t ftm_channel;
+
+ /** Configuration of output pin, this value is passed to kinetis_pinconfig. */
+ uint32_t pinconfig;
+
+};
+
+__EXPORT extern const struct pwm_servo_timer pwm_servo_timers[PWM_SERVO_MAX_TIMERS];
+
+/**
+ * All available servo channels. Board specific.
+ * Essentially, this array maps logical channel numbers to system-specific channel structures.
+ */
+__EXPORT extern const struct pwm_servo_channel pwm_servo_channels[PWM_SERVO_MAX_CHANNELS];
+
+#endif
diff --git a/src/drivers/kinetis/module.mk b/src/drivers/kinetis/module.mk
new file mode 100644
index 000000000..2dbf51011
--- /dev/null
+++ b/src/drivers/kinetis/module.mk
@@ -0,0 +1,3 @@
+SRCS = up_cxxinitialize.c drv_pwm_servo.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/kinetis/up_cxxinitialize.c b/src/drivers/kinetis/up_cxxinitialize.c
new file mode 100644
index 000000000..6c55db6ff
--- /dev/null
+++ b/src/drivers/kinetis/up_cxxinitialize.c
@@ -0,0 +1,147 @@
+/************************************************************************************
+ * configs/stm32f4discovery/src/up_cxxinitialize.c
+ * arch/arm/src/board/up_cxxinitialize.c
+ *
+ * Copyright (C) 2012 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 <nuttx/config.h>
+
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Debug ****************************************************************************/
+/* Non-standard debug that may be enabled just for testing the static constructors */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_CXX
+#endif
+
+#ifdef CONFIG_DEBUG_CXX
+# define cxxdbg dbg
+# define cxxlldbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define cxxvdbg vdbg
+# define cxxllvdbg llvdbg
+# else
+# define cxxvdbg(x...)
+# define cxxllvdbg(x...)
+# endif
+#else
+# define cxxdbg(x...)
+# define cxxlldbg(x...)
+# define cxxvdbg(x...)
+# define cxxllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+/* This type defines one entry in initialization array */
+
+typedef void (*initializer_t)(void);
+
+/************************************************************************************
+ * External references
+ ************************************************************************************/
+/* _sinit and _einit are symbols exported by the linker script that mark the
+ * beginning and the end of the C++ initialization section.
+ */
+
+extern initializer_t _sinit;
+extern initializer_t _einit;
+
+/* _stext and _etext are symbols exported by the linker script that mark the
+ * beginning and the end of text.
+ */
+
+extern uint32_t _stext;
+extern uint32_t _etext;
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: up_cxxinitialize
+ *
+ * Description:
+ * If C++ and C++ static constructors are supported, then this function
+ * must be provided by board-specific logic in order to perform
+ * initialization of the static C++ class instances.
+ *
+ * This function should then be called in the application-specific
+ * user_start logic in order to perform the C++ initialization. NOTE
+ * that no component of the core NuttX RTOS logic is involved; This
+ * function defintion only provides the 'contract' between application
+ * specific C++ code and platform-specific toolchain support
+ *
+ ***************************************************************************/
+
+__EXPORT void up_cxxinitialize(void)
+{
+ initializer_t *initp;
+
+ cxxdbg("_sinit: %p _einit: %p _stext: %p _etext: %p\n",
+ &_sinit, &_einit, &_stext, &_etext);
+
+ /* Visit each entry in the initialzation table */
+
+ for (initp = &_sinit; initp != &_einit; initp++)
+ {
+ initializer_t initializer = *initp;
+ cxxdbg("initp: %p initializer: %p\n", initp, initializer);
+
+ /* Make sure that the address is non-NULL and lies in the text region
+ * defined by the linker script. Some toolchains may put NULL values
+ * or counts in the initialization table
+ */
+
+ if ((void*)initializer > (void*)&_stext && (void*)initializer < (void*)&_etext)
+ {
+ cxxdbg("Calling %p\n", initializer);
+ initializer();
+ }
+ }
+}
diff --git a/src/examples/pwm/module.mk b/src/examples/pwm/module.mk
new file mode 100644
index 000000000..5e9e9e2ab
--- /dev/null
+++ b/src/examples/pwm/module.mk
@@ -0,0 +1,3 @@
+
+MODULE_COMMAND = pwm
+SRCS = pwm.c
diff --git a/src/examples/pwm/pwm.c b/src/examples/pwm/pwm.c
new file mode 100644
index 000000000..a40da17e7
--- /dev/null
+++ b/src/examples/pwm/pwm.c
@@ -0,0 +1,18 @@
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <errno.h>
+#include <stdlib.h>
+#include <stdbool.h>
+
+#include <drivers/drv_pwm_output.h>
+
+__EXPORT int pwm_main(int argc, char *argv[]);
+
+int pwm_main(int args, char *argv[]) {
+ printf("set pwm0 to %d us\n", atoi(argv[1]));
+
+ up_pwm_servo_init(1);
+ up_pwm_servo_arm(true);
+ up_pwm_servo_set(0, atoi(argv[1]));
+ return 0;
+}
diff --git a/src/modules/helloworld/helloworld.c b/src/modules/helloworld/helloworld.c
deleted file mode 100644
index 5b5912125..000000000
--- a/src/modules/helloworld/helloworld.c
+++ /dev/null
@@ -1,10 +0,0 @@
-#include <nuttx/config.h>
-#include <stdio.h>
-#include <errno.h>
-
-__EXPORT int helloworld_main(int argc, char *argv[]);
-
-int helloworld_main(int argc, char *argv[]) {
- printf("Hello world!\n");
- return 0;
-}
diff --git a/src/modules/helloworld/module.mk b/src/modules/helloworld/module.mk
deleted file mode 100644
index f117ae447..000000000
--- a/src/modules/helloworld/module.mk
+++ /dev/null
@@ -1,3 +0,0 @@
-
-MODULE_COMMAND = helloworld
-SRCS = helloworld.c