Cleanup and refactor of the PX4IO firmware and board support. Builds, not tested yet.

This commit is contained in:
px4dev 2012-11-01 23:42:36 -07:00
parent 82c4dbaaa8
commit ea539031da
39 changed files with 401 additions and 2572 deletions

View File

@ -36,5 +36,6 @@
#
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
LIBNAME = brd_px4fmu
include $(APPDIR)/mk/app.mk

View File

@ -57,7 +57,6 @@
#include <nuttx/i2c.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/arch.h>
#include "stm32_internal.h"
#include "px4fmu_internal.h"

View File

@ -0,0 +1,41 @@
############################################################################
#
# 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.
#
############################################################################
#
# Board-specific startup code for the PX4IO
#
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
LIBNAME = brd_px4io
include $(APPDIR)/mk/app.mk

View File

@ -1,82 +1,100 @@
/************************************************************************************
* configs/stm3210e-eval/src/up_boot.c
* arch/arm/src/board/up_boot.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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 <arch/board/board.h>
#include "up_arch.h"
#include "px4io_internal.h"
#include <arch/board/up_hrt.h>
#include <arch/board/drv_pwm_servo.h>
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* 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.
*
************************************************************************************/
void stm32_boardinitialize(void)
{
/* Configure on-board LEDs if LED support has been selected. */
#ifdef CONFIG_ARCH_LEDS
up_ledinit();
#endif
}
/****************************************************************************
*
* 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 px4io_init.c
*
* PX4IO-specific early startup code. This file implements the
* nsh_archinitialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/arch.h>
#include "stm32_internal.h"
#include "px4io_internal.h"
#include "stm32_uart.h"
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_led.h>
#include <drivers/drv_pwm_output.h>
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* 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.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
/* configure the high-resolution time/callout interface */
#ifdef CONFIG_HRT_TIMER
hrt_init();
#endif
/* configure GPIOs */
stm32_configgpio(GPIO_ACC1_PWR_EN);
stm32_configgpio(GPIO_ACC2_PWR_EN);
stm32_configgpio(GPIO_SERVO_PWR_EN);
stm32_configgpio(GPIO_RELAY1_EN);
stm32_configgpio(GPIO_RELAY2_EN);
stm32_configgpio(GPIO_LED1);
stm32_configgpio(GPIO_LED2);
stm32_configgpio(GPIO_LED3);
stm32_configgpio(GPIO_ACC_OC_DETECT);
stm32_configgpio(GPIO_SERVO_OC_DETECT);
stm32_configgpio(GPIO_BTN_SAFETY);
}

View File

@ -35,8 +35,7 @@
* @file PX4IO hardware definitions.
*/
#ifndef __CONFIGS_PX4IO_SRC_PX4IO_INTERNAL_H
#define __CONFIGS_PX4IO_SRC_PX4IO_INTERNAL_H
#pragma once
/************************************************************************************
* Included Files
@ -46,6 +45,8 @@
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_internal.h>
/************************************************************************************
* Definitions
************************************************************************************/
@ -97,21 +98,3 @@
#define GPIO_RELAY1_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN13)
#define GPIO_RELAY2_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN12)
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public data
************************************************************************************/
#ifndef __ASSEMBLY__
/************************************************************************************
* Public Functions
************************************************************************************/
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_PX4IO_SRC_PX4IO_INTERNAL_H */

View File

@ -0,0 +1,123 @@
/****************************************************************************
*
* 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 px4fmu_pwm_servo.c
*
* Configuration data for the stm32 pwm_servo driver.
*
* Note that these arrays must always be fully-sized.
*/
#include <stdint.h>
#include <drivers/stm32/drv_pwm_servo.h>
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
#include <stm32_internal.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
{
.base = STM32_TIM2_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM2EN,
.clock_freq = STM32_APB1_TIM2_CLKIN
},
{
.base = STM32_TIM3_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM3EN,
.clock_freq = STM32_APB1_TIM3_CLKIN
},
{
.base = STM32_TIM4_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM4EN,
.clock_freq = STM32_APB1_TIM4_CLKIN
}
};
__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
{
.gpio = GPIO_TIM2_CH1OUT,
.timer_index = 0,
.timer_channel = 1,
.default_value = 1000,
},
{
.gpio = GPIO_TIM2_CH2OUT,
.timer_index = 0,
.timer_channel = 2,
.default_value = 1000,
},
{
.gpio = GPIO_TIM4_CH3OUT,
.timer_index = 2,
.timer_channel = 3,
.default_value = 1000,
},
{
.gpio = GPIO_TIM4_CH4OUT,
.timer_index = 2,
.timer_channel = 4,
.default_value = 1000,
},
{
.gpio = GPIO_TIM3_CH1OUT,
.timer_index = 1,
.timer_channel = 1,
.default_value = 1000,
},
{
.gpio = GPIO_TIM3_CH2OUT,
.timer_index = 1,
.timer_channel = 2,
.default_value = 1000,
},
{
.gpio = GPIO_TIM3_CH3OUT,
.timer_index = 1,
.timer_channel = 3,
.default_value = 1000,
},
{
.gpio = GPIO_TIM3_CH4OUT,
.timer_index = 1,
.timer_channel = 4,
.default_value = 1000,
}
};

View File

@ -67,6 +67,38 @@
#endif
#ifdef CONFIG_ARCH_BOARD_PX4IO
/*
* PX4IO GPIO numbers.
*
* XXX note that these are here for reference/future use; currently
* there is no good way to wire these up without a common STM32 GPIO
* driver, which isn't implemented yet.
*/
/* outputs */
# define GPIO_ACC1_POWER (1<<0) /**< accessory power 1 */
# define GPIO_ACC2_POWER (1<<1) /**< accessory power 2 */
# define GPIO_SERVO_POWER (1<<2) /**< servo power */
# define GPIO_RELAY1 (1<<3) /**< relay 1 */
# define GPIO_RELAY2 (1<<4) /**< relay 2 */
# define GPIO_LED_BLUE (1<<5) /**< blue LED */
# define GPIO_LED_AMBER (1<<6) /**< amber/red LED */
# define GPIO_LED_SAFETY (1<<7) /**< safety LED */
/* inputs */
# define GPIO_ACC_OVERCURRENT (1<<8) /**< accessory 1/2 overcurrent detect */
# define GPIO_SERVO_OVERCURRENT (1<<9) /**< servo overcurrent detect */
# define GPIO_SAFETY_BUTTON (1<<10) /**< safety button pressed */
/**
* Default GPIO device - other devices may also support this protocol if
* they also export GPIO-like things. This is always the GPIOs on the
* main board.
*/
# define GPIO_DEVICE_PATH "/dev/px4io"
#endif
#ifndef GPIO_DEVICE_PATH
# error No GPIO support for this board.
#endif

View File

@ -50,6 +50,7 @@
#define LED_AMBER 0
#define LED_RED 0 /* some boards have red rather than amber */
#define LED_BLUE 1
#define LED_SAFETY 2
#define LED_ON _IOC(_LED_BASE, 0)
#define LED_OFF _IOC(_LED_BASE, 1)
@ -59,6 +60,6 @@ __BEGIN_DECLS
/*
* Initialise the LED driver.
*/
__EXPORT extern void drv_led_start();
__EXPORT extern void drv_led_start(void);
__END_DECLS

View File

@ -73,7 +73,7 @@
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/rc_channels.h>
#include "px4io/protocol.h"
#include <px4io/protocol.h>
#include "uploader.h"

View File

@ -276,6 +276,17 @@ static void hrt_call_invoke(void);
* Specific registers and bits used by PPM sub-functions
*/
#ifdef CONFIG_HRT_PPM
/*
* If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it.
*/
# ifndef GTIM_CCER_CC1NP
# define GTIM_CCER_CC1NP 0
# define GTIM_CCER_CC2NP 0
# define GTIM_CCER_CC3NP 0
# define GTIM_CCER_CC4NP 0
# define PPM_EDGE_FLIP
# endif
# if HRT_PPM_CHANNEL == 1
# define rCCR_PPM rCCR1 /* capture register for PPM */
# define DIER_PPM GTIM_DIER_CC1IE /* capture interrupt (non-DMA mode) */
@ -284,6 +295,7 @@ static void hrt_call_invoke(void);
# define CCMR1_PPM 1 /* not on TI1/TI2 */
# define CCMR2_PPM 0 /* on TI3, not on TI4 */
# define CCER_PPM (GTIM_CCER_CC1E | GTIM_CCER_CC1P | GTIM_CCER_CC1NP) /* CC1, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC1P
# elif HRT_PPM_CHANNEL == 2
# define rCCR_PPM rCCR2 /* capture register for PPM */
# define DIER_PPM GTIM_DIER_CC2IE /* capture interrupt (non-DMA mode) */
@ -292,6 +304,7 @@ static void hrt_call_invoke(void);
# define CCMR1_PPM 2 /* not on TI1/TI2 */
# define CCMR2_PPM 0 /* on TI3, not on TI4 */
# define CCER_PPM (GTIM_CCER_CC2E | GTIM_CCER_CC2P | GTIM_CCER_CC2NP) /* CC2, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC2P
# elif HRT_PPM_CHANNEL == 3
# define rCCR_PPM rCCR3 /* capture register for PPM */
# define DIER_PPM GTIM_DIER_CC3IE /* capture interrupt (non-DMA mode) */
@ -300,6 +313,7 @@ static void hrt_call_invoke(void);
# define CCMR1_PPM 0 /* not on TI1/TI2 */
# define CCMR2_PPM 1 /* on TI3, not on TI4 */
# define CCER_PPM (GTIM_CCER_CC3E | GTIM_CCER_CC3P | GTIM_CCER_CC3NP) /* CC3, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC3P
# elif HRT_PPM_CHANNEL == 4
# define rCCR_PPM rCCR4 /* capture register for PPM */
# define DIER_PPM GTIM_DIER_CC4IE /* capture interrupt (non-DMA mode) */
@ -308,6 +322,7 @@ static void hrt_call_invoke(void);
# define CCMR1_PPM 0 /* not on TI1/TI2 */
# define CCMR2_PPM 2 /* on TI3, not on TI4 */
# define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC4P
# else
# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set
# endif
@ -532,9 +547,14 @@ hrt_tim_isr(int irq, void *context)
#ifdef CONFIG_HRT_PPM
/* was this a PPM edge? */
if (status & (SR_INT_PPM | SR_OVF_PPM))
hrt_ppm_decode(status);
if (status & (SR_INT_PPM | SR_OVF_PPM)) {
/* if required, flip edge sensitivity */
# ifdef PPM_EDGE_FLIP
rCCER ^= CCER_PPM_FLIP;
# endif
hrt_ppm_decode(status);
}
#endif
/* was this a timer tick? */

View File

@ -42,7 +42,7 @@
#include <drivers/drv_pwm_output.h>
/* configuration limits */
#define PWM_SERVO_MAX_TIMERS 2
#define PWM_SERVO_MAX_TIMERS 4
#define PWM_SERVO_MAX_CHANNELS 8
/* array of timers dedicated to PWM servo use */
@ -53,9 +53,6 @@ struct pwm_servo_timer {
uint32_t clock_freq;
};
/* supplied by board-specific code */
__EXPORT extern const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS];
/* array of channels in logical order */
struct pwm_servo_channel {
uint32_t gpio;
@ -64,4 +61,6 @@ struct pwm_servo_channel {
servo_position_t default_value;
};
/* supplied by board-specific code */
__EXPORT extern const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS];
__EXPORT extern const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS];

View File

@ -121,7 +121,6 @@ int test_ppm(int argc, char *argv[])
int test_tone(int argc, char *argv[])
{
#ifdef CONFIG_TONE_ALARM
int fd, result;
unsigned long tone;
@ -171,7 +170,6 @@ out:
if (fd >= 0)
close(fd);
#endif
return 0;
}

View File

@ -39,11 +39,10 @@
# Note that we pull a couple of specific files from the systemlib, since
# we can't support it all.
#
CSRCS = comms.c \
mixer.c \
px4io.c \
safety.c \
../systemlib/hx_stream.c \
../systemlib/perf_counter.c
CSRCS = $(wildcard *.c) \
../systemlib/hx_stream.c \
../systemlib/perf_counter.c
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
include $(APPDIR)/mk/app.mk

View File

@ -93,7 +93,7 @@ comms_check(void)
last_report_time = now;
/* populate the report */
for (unsigned i = 0; i < system_state.rc_channels; i++)
for (int i = 0; i < system_state.rc_channels; i++)
report.rc_channel[i] = system_state.rc_channel_data[i];
report.channel_count = system_state.rc_channels;
report.armed = system_state.armed;

View File

@ -45,18 +45,13 @@
#include <errno.h>
#include <fcntl.h>
#include <arch/board/drv_ppm_input.h>
#include <arch/board/drv_pwm_servo.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
#include <systemlib/ppm_decode.h>
#include "px4io.h"
#ifdef CONFIG_DISABLE_MQUEUE
# error Mixer requires message queues - set CONFIG_DISABLE_MQUEUE=n and try again
#endif
static mqd_t input_queue;
/*
* Count of periodic calls in which we have no data.
*/
@ -89,9 +84,6 @@ static void mixer_get_rc_input(void);
*/
static void mixer_update(int mixer, uint16_t *inputs, int input_count);
/* servo driver handle */
int mixer_servo_fd;
/* current servo arm/disarm state */
bool mixer_servos_armed;
@ -106,14 +98,6 @@ struct mixer {
int
mixer_init(const char *mq_name)
{
/* open the control input queue; this should always exist */
input_queue = mq_open(mq_name, O_RDONLY | O_NONBLOCK);
ASSERTCODE((input_queue >= 0), A_INPUTQ_OPEN_FAIL);
/* open the servo driver */
mixer_servo_fd = open("/dev/pwm_servo", O_WRONLY);
ASSERTCODE((mixer_servo_fd >= 0), A_SERVO_OPEN_FAIL);
/* look for control data at 50Hz */
hrt_call_every(&mixer_input_call, 1000, 20000, mixer_tick, NULL);
@ -176,9 +160,8 @@ mixer_tick(void *arg)
* If we are armed, update the servo output.
*/
if (system_state.armed)
ioctl(mixer_servo_fd, PWM_SERVO_SET(i), mixers[i].current_value);
up_pwm_servo_set(i, mixers[i].current_value);
}
}
/*
@ -187,12 +170,12 @@ mixer_tick(void *arg)
should_arm = system_state.armed && (control_count > 0);
if (should_arm && !mixer_servos_armed) {
/* need to arm, but not armed */
ioctl(mixer_servo_fd, PWM_SERVO_ARM, 0);
up_pwm_servo_arm(true);
mixer_servos_armed = true;
} else if (!should_arm && mixer_servos_armed) {
/* armed but need to disarm*/
ioctl(mixer_servo_fd, PWM_SERVO_DISARM, 0);
/* armed but need to disarm */
up_pwm_servo_arm(false);
mixer_servos_armed = false;
}
}
@ -200,22 +183,20 @@ mixer_tick(void *arg)
static void
mixer_get_rc_input(void)
{
ssize_t len;
/*
* Pull channel data from the message queue into the system state structure.
* XXX currently only supporting PPM
*
* XXX check timestamp to ensure current
*/
len = mq_receive(input_queue, &system_state.rc_channel_data, sizeof(system_state.rc_channel_data), NULL);
/*
* If we have data, update the count and status.
*/
if (len > 0) {
system_state.rc_channels = len / sizeof(system_state.rc_channel_data[0]);
if (ppm_decoded_channels > 0) {
mixer_input_drops = 0;
system_state.fmu_report_due = true;
/* copy channel data */
system_state.rc_channels = ppm_decoded_channels;
for (unsigned i = 0; i < ppm_decoded_channels; i++)
system_state.rc_channel_data[i] = ppm_buffer[i];
} else {
/*
* No data; count the 'frame drops' and once we hit the limit

View File

@ -47,9 +47,7 @@
#include <nuttx/clock.h>
#include <arch/board/up_boardinitialize.h>
#include <arch/board/drv_gpio.h>
#include <arch/board/drv_ppm_input.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
#include "px4io.h"
@ -73,8 +71,8 @@ int user_start(int argc, char *argv[])
bool heartbeat = false;
bool failsafe = false;
/* Do board init */
(void)up_boardinitialize();
/* configure the PWM outputs */
up_pwm_servo_init(0xff);
/* print some startup info */
lib_lowprintf("\nPX4IO: starting\n");
@ -84,21 +82,14 @@ int user_start(int argc, char *argv[])
/* start the software timer service */
hrt_call_every(&timer_tick_call, 1000, 1000, timer_tick, NULL);
/* Open the GPIO driver so we can do LEDs and the like. */
gpio_fd = open("/dev/gpio", 0);
ASSERTCODE((gpio_fd >= 0), A_GPIO_OPEN_FAIL);
/* default all the LEDs to off while we start */
LED_AMBER(heartbeat);
LED_BLUE(failsafe);
LED_AMBER(false);
LED_BLUE(false);
LED_SAFETY(false);
/* turn on servo power */
POWER_SERVO(true);
/* configure the PPM input driver */
ppm_input_init(rc_input_mq_name);
/* start the mixer */
mixer_init(rc_input_mq_name);
@ -123,18 +114,19 @@ int user_start(int argc, char *argv[])
/* blink the heartbeat LED */
if (timers[TIMER_BLINK_AMBER] == 0) {
timers[TIMER_BLINK_AMBER] = 250;
LED_AMBER((heartbeat = !heartbeat));
LED_AMBER(heartbeat = !heartbeat);
}
/* blink the failsafe LED if we don't have FMU input */
if (!system_state.mixer_use_fmu) {
if (timers[TIMER_BLINK_BLUE] == 0) {
timers[TIMER_BLINK_BLUE] = 125;
LED_BLUE((failsafe = !failsafe));
failsafe = !failsafe;
}
} else {
LED_BLUE((failsafe = false));
failsafe = false;
}
LED_BLUE(failsafe);
/* print some simple status */
if (timers[TIMER_STATUS_PRINT] == 0) {
@ -147,7 +139,6 @@ int user_start(int argc, char *argv[])
system_state.rc_channels
);
}
}
/* Should never reach here */

View File

@ -32,10 +32,18 @@
****************************************************************************/
/**
* @file General defines and structures for the PX4IO module firmware.
* @file px4io.h
*
* General defines and structures for the PX4IO module firmware.
*/
#include <arch/board/drv_gpio.h>
#include <nuttx/config.h>
#include <stdbool.h>
#include <stdint.h>
#include <drivers/boards/px4io/px4io_internal.h>
#include "protocol.h"
/*
@ -102,21 +110,19 @@ extern volatile int timers[TIMER_NUM_TIMERS];
/*
* GPIO handling.
*/
extern int gpio_fd;
#define LED_AMBER(_s) stm32_gpiowrite(GPIO_LED1, !(_s))
#define LED_BLUE(_s) stm32_gpiowrite(GPIO_LED2, !(_s))
#define LED_SAFETY(_s) stm32_gpiowrite(GPIO_LED3, !(_s))
#define POWER_SERVO(_s) ioctl(gpio_fd, GPIO_SET(GPIO_SERVO_POWER), (_s))
#define POWER_ACC1(_s) ioctl(gpio_fd, GPIO_SET(GPIO_SERVO_ACC1), (_s))
#define POWER_ACC2(_s) ioctl(gpio_fd, GPIO_SET(GPIO_SERVO_ACC2), (_s))
#define POWER_RELAY1(_s) ioctl(gpio_fd, GPIO_SET(GPIO_RELAY1, (_s))
#define POWER_RELAY2(_s) ioctl(gpio_fd, GPIO_SET(GPIO_RELAY2, (_s))
#define POWER_SERVO(_s) stm32_gpiowrite(GPIO_SERVO_PWR_EN, (_s))
#define POWER_ACC1(_s) stm32_gpiowrite(GPIO_SERVO_ACC1_EN, (_s))
#define POWER_ACC2(_s) stm32_gpiowrite(GPIO_SERVO_ACC2_EN, (_s))
#define POWER_RELAY1(_s) stm32_gpiowrite(GPIO_RELAY1_EN, (_s))
#define POWER_RELAY2(_s) stm32_gpiowrite(GPIO_RELAY2_EN, (_s))
#define LED_AMBER(_s) ioctl(gpio_fd, GPIO_SET(GPIO_LED_AMBER), !(_s))
#define LED_BLUE(_s) ioctl(gpio_fd, GPIO_SET(GPIO_LED_BLUE), !(_s))
#define LED_SAFETY(_s) ioctl(gpio_fd, GPIO_SET(GPIO_LED_SAFETY), !(_s))
#define OVERCURRENT_ACC ioctl(gpio_fd, GPIO_GET(GPIO_ACC_OVERCURRENT), 0)
#define OVERCURRENT_SERVO ioctl(gpio_fd, GPIO_GET(GPIO_SERVO_OVERCURRENT), 0)
#define BUTTON_SAFETY ioctl(gpio_fd, GPIO_GET(GPIO_SAFETY_BUTTON), 0)
#define OVERCURRENT_ACC stm32_gpioread(GPIO_ACC_OC_DETECT)
#define OVERCURRENT_SERVO stm32_gpioread(GPIO_SERVO_OC_DETECT
#define BUTTON_SAFETY stm32_gpioread(GPIO_BTN_SAFETY)
/*
* Mixer

View File

@ -46,9 +46,6 @@
#include <nuttx/clock.h>
#include <arch/board/up_boardinitialize.h>
#include <arch/board/drv_gpio.h>
#include <arch/board/drv_ppm_input.h>
#include <drivers/drv_hrt.h>
#include "px4io.h"

View File

@ -63,6 +63,7 @@
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
#include <systemlib/ppm_decode.h>
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
@ -90,19 +91,6 @@
#define BAT_VOL_LOWPASS_2 0.01f
#define VOLTAGE_BATTERY_IGNORE_THRESHOLD_VOLTS 3.5f
#ifdef CONFIG_HRT_PPM
extern "C" {
extern uint16_t ppm_buffer[];
extern unsigned ppm_decoded_channels;
extern uint64_t ppm_last_valid_decode;
}
/* PPM Settings */
# define PPM_MIN 1000
# define PPM_MAX 2000
# define PPM_MID (PPM_MIN+PPM_MAX)/2
#endif
/**
* Sensor app start / stop handling function
*

View File

@ -46,12 +46,17 @@
*/
#define PPM_MAX_CHANNELS 12
/* PPM input nominal min/max values */
#define PPM_MIN 1000
#define PPM_MAX 2000
#define PPM_MID ((PPM_MIN + PPM_MAX) / 2)
__BEGIN_DECLS
/*
* PPM decoder state
*/
__EXPORT extern uint16_t ppm_buffer[]; /**< decoded PPM channel values */
__EXPORT extern uint16_t ppm_buffer[PPM_MAX_CHANNELS]; /**< decoded PPM channel values */
__EXPORT extern unsigned ppm_decoded_channels; /**< count of decoded channels */
__EXPORT extern hrt_abstime ppm_last_valid_decode; /**< timestamp of the last valid decode */

View File

@ -188,18 +188,6 @@
# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
#endif
/* LED definitions ******************************************************************/
/* PX4 has two LEDs that we will encode as: */
#define LED_STARTED 0 /* LED? */
#define LED_HEAPALLOCATE 1 /* LED? */
#define LED_IRQSENABLED 2 /* LED? + LED? */
#define LED_STACKCREATED 3 /* LED? */
#define LED_INIRQ 4 /* LED? + LED? */
#define LED_SIGNAL 5 /* LED? + LED? */
#define LED_ASSERTION 6 /* LED? + LED? + LED? */
#define LED_PANIC 7 /* N/C + N/C + N/C + LED? */
/* Alternate function pin selections ************************************************/
/*

View File

@ -306,25 +306,9 @@ CONFIG_USART6_RXDMA=y
# set HRT_PPM_CHANNEL to the timer capture/compare channel to be
# used, and define GPIO_PPM_IN to configure the appropriate timer
# GPIO.
# CONFIG_TONE_ALARM
# Enables the tone alarm (buzzer) driver The board definition must
# set TONE_ALARM_TIMER and TONE_ALARM_CHANNEL to the timer and
# capture/compare channels to be used.
# CONFIG_PWM_SERVO
# Enables the PWM servo driver. The driver configuration must be
# supplied by the board support at initialisation time.
# Note that USART2 must be disabled on the PX4 board for this to
# be available.
# CONFIG_MULTIPORT
# Enabled support for run-time (or EEPROM based boot-time) configuration
# of ports for different functions (e.g. USART2 or ARDrone or PWM out)
#
#
CONFIG_HRT_TIMER=y
CONFIG_HRT_PPM=y
CONFIG_TONE_ALARM=y
CONFIG_PWM_SERVO=n
CONFIG_MULTIPORT=n
#
# STM32F40xxx specific SPI device driver settings

View File

@ -47,9 +47,9 @@
# include <stdint.h>
# include <stdbool.h>
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
#include <stm32_rcc.h>
#include <stm32_sdio.h>
#include <stm32_internal.h>
/************************************************************************************
* Definitions
@ -116,12 +116,6 @@
# define GPIO_PPM_IN GPIO_TIM1_CH1IN
#endif
/*
* PWM
*
* PWM configuration is provided via the configuration structure in up_boardinitialize.c
*/
/************************************************************************************
* Public Data
************************************************************************************/
@ -151,17 +145,5 @@ extern "C" {
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 */

View File

@ -1,67 +0,0 @@
/****************************************************************************
*
* 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);

View File

@ -1,100 +0,0 @@
/****************************************************************************
*
* 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);

View File

@ -1,94 +0,0 @@
/****************************************************************************
*
* 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);

View File

@ -1,43 +0,0 @@
/****************************************************************************
*
* 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

View File

@ -1,129 +0,0 @@
/****************************************************************************
*
* 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_ */

View File

@ -31,4 +31,7 @@
#
############################################################################
CONFIGURED_APPS += drivers/boards/px4io
CONFIGURED_APPS += drivers/stm32
CONFIGURED_APPS += px4io

View File

@ -84,7 +84,7 @@ CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=y
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=n
CONFIG_ARMV7M_CMNVECTOR=y
@ -204,7 +204,6 @@ CONFIG_USART3_2STOP=0
#
CONFIG_HRT_TIMER=y
CONFIG_HRT_PPM=y
CONFIG_PWM_SERVO=y
#
# General build options
@ -389,10 +388,10 @@ CONFIG_DISABLE_CLOCK=n
CONFIG_DISABLE_POSIX_TIMERS=y
CONFIG_DISABLE_PTHREAD=y
CONFIG_DISABLE_SIGNALS=y
CONFIG_DISABLE_MQUEUE=n
CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_MOUNTPOINT=y
CONFIG_DISABLE_ENVIRON=y
CONFIG_DISABLE_POLL=y
CONFIG_DISABLE_POLL=n
#
# Misc libc settings

View File

@ -40,17 +40,7 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = up_boot.c up_hrt.c\
drv_pwm_servo.c drv_ppm_input.c drv_gpio.c \
up_boardinitialize.c
ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
ifeq ($(CONFIG_ADC),y)
CSRCS += up_adc.c
endif
CSRCS = empty.c
COBJS = $(CSRCS:.c=$(OBJEXT))

View File

@ -1,110 +0,0 @@
/****************************************************************************
*
* 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 <nuttx/config.h>
#include <sys/types.h>
#include <stdbool.h>
#include <errno.h>
#include <arch/board/board.h>
#include <arch/board/drv_gpio.h>
#include "px4io_internal.h"
#include "stm32_gpio.h"
static int gpio_ioctl(struct file *filep, int cmd, unsigned long arg);
static const struct file_operations gpio_fops = {
.ioctl = gpio_ioctl
};
/*
* Order of initialisers in this array must match the order of
* GPIO_ definitions in drv_gpio.h
*/
static const uint32_t gpios[] = {
/* settable */
GPIO_ACC1_PWR_EN,
GPIO_ACC2_PWR_EN,
GPIO_SERVO_PWR_EN,
GPIO_RELAY1_EN,
GPIO_RELAY2_EN,
GPIO_LED1,
GPIO_LED2,
GPIO_LED3,
/* readonly */
GPIO_ACC_OC_DETECT,
GPIO_SERVO_OC_DETECT,
GPIO_BTN_SAFETY
};
int
gpio_drv_init(void)
{
int i;
/* initialise GPIOs */
for (i = 0; i < GPIO_MAX; i++)
if (gpios[i])
stm32_configgpio(gpios[i]);
/* register the device */
return register_driver("/dev/gpio", &gpio_fops, 0666, NULL);
}
static int
gpio_ioctl(struct file *filep, int cmd, unsigned long arg)
{
/* attempt to set a GPIO? */
if ((cmd >= GPIO_SET(0)) && (cmd <= GPIO_SET(GPIO_MAX_SETTABLE))) {
uint32_t gpio = gpios[cmd - GPIO_SET(0)];
if (gpio != 0) {
stm32_gpiowrite(gpio, arg ? true : false);
return 0;
}
} else if ((cmd >= GPIO_GET(0)) && (cmd <= GPIO_GET(GPIO_MAX))) {
uint32_t gpio = gpios[cmd - GPIO_GET(0)];
if (gpio != 0)
return stm32_gpioread(gpio) ? 1 : 0;
}
return -ENOTTY;
}

View File

@ -1,373 +0,0 @@
/****************************************************************************
*
* 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.
*/
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <sys/types.h>
#include <stdbool.h>
#include <assert.h>
#include <debug.h>
#include <time.h>
#include <queue.h>
#include <errno.h>
#include <string.h>
#include <stdio.h>
#include <fcntl.h>
#include <arch/board/board.h>
#include <arch/board/drv_ppm_input.h>
#include <arch/board/up_hrt.h>
#include "chip.h"
#include "up_internal.h"
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32_gpio.h"
#include "stm32_tim.h"
#ifdef CONFIG_HRT_PPM
# ifndef CONFIG_HRT_TIMER
# error CONFIG_HRT_PPM requires CONFIG_HRT_TIMER
# endif
/*
* PPM decoder tuning parameters.
*
* The PPM decoder works as follows.
*
* Initially, the decoder waits in the UNSYNCH state for two edges
* separated by PPM_MIN_START. Once the second edge is detected,
* the decoder moves to the ARM state.
*
* The ARM state expects an edge within PPM_MAX_PULSE_WIDTH, being the
* timing mark for the first channel. If this is detected, it moves to
* the INACTIVE state.
*
* The INACTIVE phase waits for and discards the next edge, as it is not
* significant. Once the edge is detected, it moves to the ACTIVE stae.
*
* The ACTIVE state expects an edge within PPM_MAX_PULSE_WIDTH, and when
* received calculates the time from the previous mark and records
* this time as the value for the next channel.
*
* If at any time waiting for an edge, the delay from the previous edge
* exceeds PPM_MIN_START the frame is deemed to have ended and the recorded
* values are advertised to clients.
*/
#define PPM_MAX_PULSE_WIDTH 500 /* maximum width of a pulse */
#define PPM_MIN_CHANNEL_VALUE 800 /* shortest valid channel signal */
#define PPM_MAX_CHANNEL_VALUE 2200 /* longest valid channel signal */
#define PPM_MIN_START 2500 /* shortest valid start gap */
/* Input timeout - after this interval we assume signal is lost */
#define PPM_INPUT_TIMEOUT 100 * 1000 /* 100ms */
/* Number of same-sized frames required to 'lock' */
#define PPM_CHANNEL_LOCK 3 /* should be less than the input timeout */
/* decoded PPM buffer */
#define PPM_MIN_CHANNELS 4
#define PPM_MAX_CHANNELS 12
static uint16_t ppm_buffer[PPM_MAX_CHANNELS];
static unsigned ppm_decoded_channels;
static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
/* PPM decoder state machine */
static struct {
uint16_t last_edge; /* last capture time */
uint16_t last_mark; /* last significant edge */
unsigned next_channel;
enum {
UNSYNCH = 0,
ARM,
ACTIVE,
INACTIVE
} phase;
} ppm;
/* last time we got good data */
static hrt_abstime ppm_timestamp;
#ifndef CONFIG_DISABLE_MQUEUE
/* message queue we advertise PPM data on */
static mqd_t ppm_message_queue;
#endif
/* set if PPM data has not been read */
static bool ppm_fresh_data;
/* PPM device node file ops */
static int ppm_read(struct file *filp, char *buffer, size_t len);
static int ppm_ioctl(struct file *filp, int cmd, unsigned long arg);
static const struct file_operations ppm_fops = {
.read = ppm_read,
.ioctl = ppm_ioctl
};
/*
* Initialise the PPM system for client use.
*/
int
ppm_input_init(const char *mq_name)
{
int err;
/* configure the PPM input pin */
stm32_configgpio(GPIO_PPM_IN);
/* and register the device node */
if (OK != (err = register_driver(PPM_DEVICE_NODE, &ppm_fops, 0666, NULL)))
return err;
#ifndef CONFIG_DISABLE_MQUEUE
if (mq_name != NULL) {
/* create the message queue */
struct mq_attr attr = {
.mq_maxmsg = 1,
.mq_msgsize = sizeof(ppm_buffer)
};
ppm_message_queue = mq_open(mq_name, O_WRONLY | O_CREAT | O_NONBLOCK, 0666, &attr);
if (ppm_message_queue < 0)
return -errno;
}
#endif
return OK;
}
/*
* Handle the PPM decoder state machine.
*/
void
ppm_input_decode(bool reset, uint16_t count)
{
uint16_t width;
uint16_t interval;
unsigned i;
/* if we missed an edge, we have to give up */
if (reset)
goto error;
/* how long since the last edge? */
width = count - ppm.last_edge;
ppm.last_edge = count;
/*
* If this looks like a start pulse, then push the last set of values
* and reset the state machine.
*
* Note that this is not a "high performance" design; it implies a whole
* frame of latency between the pulses being received and their being
* considered valid.
*/
if (width >= PPM_MIN_START) {
/*
* If the number of channels changes unexpectedly, we don't want
* to just immediately jump on the new count as it may be a result
* of noise or dropped edges. Instead, take a few frames to settle.
*/
if (ppm.next_channel != ppm_decoded_channels) {
static int new_channel_count;
static int new_channel_holdoff;
if (new_channel_count != ppm.next_channel) {
/* start the lock counter for the new channel count */
new_channel_count = ppm.next_channel;
new_channel_holdoff = PPM_CHANNEL_LOCK;
} else if (new_channel_holdoff > 0) {
/* this frame matched the last one, decrement the lock counter */
new_channel_holdoff--;
} else {
/* we have seen PPM_CHANNEL_LOCK frames with the new count, accept it */
ppm_decoded_channels = new_channel_count;
new_channel_count = 0;
}
} else {
/* frame channel count matches expected, let's use it */
if (ppm.next_channel > PPM_MIN_CHANNELS) {
for (i = 0; i < ppm.next_channel; i++)
ppm_buffer[i] = ppm_temp_buffer[i];
ppm_timestamp = hrt_absolute_time();
ppm_fresh_data = true;
#ifndef CONFIG_DISABLE_MQUEUE
/* advertise the new data to the message queue */
mq_send(ppm_message_queue, ppm_buffer, ppm_decoded_channels * sizeof(ppm_buffer[0]), 0);
#endif
}
}
/* reset for the next frame */
ppm.next_channel = 0;
/* next edge is the reference for the first channel */
ppm.phase = ARM;
return;
}
switch (ppm.phase) {
case UNSYNCH:
/* we are waiting for a start pulse - nothing useful to do here */
return;
case ARM:
/* we expect a pulse giving us the first mark */
if (width > PPM_MAX_PULSE_WIDTH)
goto error; /* pulse was too long */
/* record the mark timing, expect an inactive edge */
ppm.last_mark = count;
ppm.phase = INACTIVE;
return;
case INACTIVE:
/* this edge is not interesting, but now we are ready for the next mark */
ppm.phase = ACTIVE;
/* note that we don't bother looking at the timing of this edge */
return;
case ACTIVE:
/* we expect a well-formed pulse */
if (width > PPM_MAX_PULSE_WIDTH)
goto error; /* pulse was too long */
/* determine the interval from the last mark */
interval = count - ppm.last_mark;
ppm.last_mark = count;
/* if the mark-mark timing is out of bounds, abandon the frame */
if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE))
goto error;
/* if we have room to store the value, do so */
if (ppm.next_channel < PPM_MAX_CHANNELS)
ppm_temp_buffer[ppm.next_channel++] = interval;
ppm.phase = INACTIVE;
return;
}
/* the state machine is corrupted; reset it */
error:
/* we don't like the state of the decoder, reset it and try again */
ppm.phase = UNSYNCH;
ppm_decoded_channels = 0;
}
static int
ppm_read(struct file *filp, char *buffer, size_t len)
{
size_t avail;
/* the size of the returned data indicates the number of channels */
avail = ppm_decoded_channels * sizeof(ppm_buffer[0]);
/* if we have not decoded a frame, that's an I/O error */
if (avail == 0)
return -EIO;
/* if the caller's buffer is too small, that's also bad */
if (len < avail)
return -EFBIG;
/* if the caller doesn't want to block, and there is no fresh data, that's EWOULDBLOCK */
if ((filp->f_oflags & O_NONBLOCK) && (!ppm_fresh_data))
return -EWOULDBLOCK;
/*
* Return the channel data.
*
* Note that we have to block the HRT while copying to avoid the
* possibility that we'll get interrupted in the middle of copying
* a single value.
*/
irqstate_t flags = irqsave();
memcpy(buffer, ppm_buffer, avail);
ppm_fresh_data = false;
irqrestore(flags);
return OK;
}
static int
ppm_ioctl(struct file *filp, int cmd, unsigned long arg)
{
switch (cmd) {
case PPM_INPUT_STATUS:
/* if we have received a frame within the timeout, the signal is "good" */
if ((hrt_absolute_time() - ppm_timestamp) < PPM_INPUT_TIMEOUT) {
*(ppm_input_status_t *)arg = PPM_STATUS_SIGNAL_CURRENT;
} else {
/* reset the number of channels so that any attempt to read data will fail */
ppm_decoded_channels = 0;
*(ppm_input_status_t *)arg = PPM_STATUS_NO_SIGNAL;
}
return OK;
case PPM_INPUT_CHANNELS:
*(ppm_input_channel_count_t *)arg = ppm_decoded_channels;
return OK;
default:
return -ENOTTY;
}
}
#endif /* CONFIG_HRT_PPM */

View File

@ -1,318 +0,0 @@
/****************************************************************************
*
* 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 Servo driver supporting PWM servos connected to STM32 timer blocks.
*
* Works with any of the 'generic' or 'advanced' STM32 timers that
* have output pins, does not require an interrupt.
*/
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include <sys/types.h>
#include <stdbool.h>
#include <debug.h>
#include <errno.h>
#include <arch/board/board.h>
#include <arch/board/drv_pwm_servo.h>
#include "stm32_gpio.h"
#include "stm32_tim.h"
#ifdef CONFIG_PWM_SERVO
static const struct pwm_servo_config *cfg;
#define REG(_tmr, _reg) (*(volatile uint32_t *)(cfg->timers[_tmr].base + _reg))
#define rCR1(_tmr) REG(_tmr, STM32_GTIM_CR1_OFFSET)
#define rCR2(_tmr) REG(_tmr, STM32_GTIM_CR2_OFFSET)
#define rSMCR(_tmr) REG(_tmr, STM32_GTIM_SMCR_OFFSET)
#define rDIER(_tmr) REG(_tmr, STM32_GTIM_DIER_OFFSET)
#define rSR(_tmr) REG(_tmr, STM32_GTIM_SR_OFFSET)
#define rEGR(_tmr) REG(_tmr, STM32_GTIM_EGR_OFFSET)
#define rCCMR1(_tmr) REG(_tmr, STM32_GTIM_CCMR1_OFFSET)
#define rCCMR2(_tmr) REG(_tmr, STM32_GTIM_CCMR2_OFFSET)
#define rCCER(_tmr) REG(_tmr, STM32_GTIM_CCER_OFFSET)
#define rCNT(_tmr) REG(_tmr, STM32_GTIM_CNT_OFFSET)
#define rPSC(_tmr) REG(_tmr, STM32_GTIM_PSC_OFFSET)
#define rARR(_tmr) REG(_tmr, STM32_GTIM_ARR_OFFSET)
#define rCCR1(_tmr) REG(_tmr, STM32_GTIM_CCR1_OFFSET)
#define rCCR2(_tmr) REG(_tmr, STM32_GTIM_CCR2_OFFSET)
#define rCCR3(_tmr) REG(_tmr, STM32_GTIM_CCR3_OFFSET)
#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET)
#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET)
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
static void
pwm_timer_init(unsigned timer)
{
/* enable the timer clock before we try to talk to it */
modifyreg32(cfg->timers[timer].clock_register, 0, cfg->timers[timer].clock_bit);
/* disable and configure the timer */
rCR1(timer) = 0;
rCR2(timer) = 0;
rSMCR(timer) = 0;
rDIER(timer) = 0;
rCCER(timer) = 0;
rCCMR1(timer) = 0;
rCCMR2(timer) = 0;
rCCER(timer) = 0;
rDCR(timer) = 0;
/* configure the timer to free-run at 1MHz */
rPSC(timer) = (cfg->timers[timer].clock_freq / 1000000) -1;
/* and update at the desired rate */
rARR(timer) = (1000000 / cfg->update_rate) - 1;
/* generate an update event; reloads the counter and all registers */
rEGR(timer) = GTIM_EGR_UG;
/* note that the timer is left disabled - arming is performed separately */
}
static void
pwm_servos_arm(bool armed)
{
/* iterate timers and arm/disarm appropriately */
for (unsigned i = 0; i < PWM_SERVO_MAX_TIMERS; i++) {
if (cfg->timers[i].base != 0)
rCR1(i) = armed ? GTIM_CR1_CEN : 0;
}
}
static void
pwm_channel_init(unsigned channel)
{
unsigned timer = cfg->channels[channel].timer_index;
/* configure the GPIO first */
stm32_configgpio(cfg->channels[channel].gpio);
/* configure the channel */
switch (cfg->channels[channel].timer_channel) {
case 1:
rCCMR1(timer) |= (6 << 4);
rCCR1(timer) = cfg->channels[channel].default_value;
rCCER(timer) |= (1 << 0);
break;
case 2:
rCCMR1(timer) |= (6 << 12);
rCCR2(timer) = cfg->channels[channel].default_value;
rCCER(timer) |= (1 << 4);
break;
case 3:
rCCMR2(timer) |= (6 << 4);
rCCR3(timer) = cfg->channels[channel].default_value;
rCCER(timer) |= (1 << 8);
break;
case 4:
rCCMR2(timer) |= (6 << 12);
rCCR4(timer) = cfg->channels[channel].default_value;
rCCER(timer) |= (1 << 12);
break;
}
}
static void
pwm_channel_set(unsigned channel, servo_position_t value)
{
if (channel >= PWM_SERVO_MAX_CHANNELS) {
lldbg("pwm_channel_set: bogus channel %u\n", channel);
return;
}
unsigned timer = cfg->channels[channel].timer_index;
/* test timer for validity */
if ((cfg->timers[timer].base == 0) ||
(cfg->channels[channel].gpio == 0))
return;
/* configure the channel */
if (value > 0)
value--;
switch (cfg->channels[channel].timer_channel) {
case 1:
rCCR1(timer) = value;
break;
case 2:
rCCR2(timer) = value;
break;
case 3:
rCCR3(timer) = value;
break;
case 4:
rCCR4(timer) = value;
break;
}
}
static servo_position_t
pwm_channel_get(unsigned channel)
{
if (channel >= PWM_SERVO_MAX_CHANNELS) {
lldbg("pwm_channel_get: bogus channel %u\n", channel);
return 0;
}
unsigned timer = cfg->channels[channel].timer_index;
servo_position_t value = 0;
/* test timer for validity */
if ((cfg->timers[timer].base == 0) ||
(cfg->channels[channel].gpio == 0))
return 0;
/* configure the channel */
switch (cfg->channels[channel].timer_channel) {
case 1:
value = rCCR1(timer);
break;
case 2:
value = rCCR2(timer);
break;
case 3:
value = rCCR3(timer);
break;
case 4:
value = rCCR4(timer);
break;
}
return value;
}
static int pwm_servo_write(struct file *filp, const char *buffer, size_t len);
static int pwm_servo_read(struct file *filp, char *buffer, size_t len);
static int pwm_servo_ioctl(struct file *filep, int cmd, unsigned long arg);
static const struct file_operations pwm_servo_fops = {
.write = pwm_servo_write,
.read = pwm_servo_read,
.ioctl = pwm_servo_ioctl
};
static int
pwm_servo_write(struct file *filp, const char *buffer, size_t len)
{
unsigned channels = len / sizeof(servo_position_t);
servo_position_t *pdata = (servo_position_t *)buffer;
unsigned i;
if (channels > PWM_SERVO_MAX_CHANNELS)
return -EIO;
for (i = 0; i < channels; i++)
pwm_channel_set(i, pdata[i]);
return i * sizeof(servo_position_t);
}
static int
pwm_servo_read(struct file *filp, char *buffer, size_t len)
{
unsigned channels = len / sizeof(servo_position_t);
servo_position_t *pdata = (servo_position_t *)buffer;
unsigned i;
if (channels > PWM_SERVO_MAX_CHANNELS)
return -EIO;
for (i = 0; i < channels; i++)
pdata[i] = pwm_channel_get(i);
return i * sizeof(servo_position_t);
}
static int
pwm_servo_ioctl(struct file *filep, int cmd, unsigned long arg)
{
/* regular ioctl? */
switch (cmd) {
case PWM_SERVO_ARM:
pwm_servos_arm(true);
return 0;
case PWM_SERVO_DISARM:
pwm_servos_arm(false);
return 0;
}
/* channel set? */
if ((cmd >= PWM_SERVO_SET(0)) && (cmd < PWM_SERVO_SET(PWM_SERVO_MAX_CHANNELS))) {
/* XXX sanity-check value? */
pwm_channel_set(cmd - PWM_SERVO_SET(0), (servo_position_t)arg);
return 0;
}
/* channel get? */
if ((cmd >= PWM_SERVO_GET(0)) && (cmd < PWM_SERVO_GET(PWM_SERVO_MAX_CHANNELS))) {
/* XXX sanity-check value? */
*(servo_position_t *)arg = pwm_channel_get(cmd - PWM_SERVO_GET(0));
return 0;
}
/* not a recognised value */
return -ENOTTY;
}
int
pwm_servo_init(const struct pwm_servo_config *config)
{
/* save a pointer to the configuration */
cfg = config;
/* do basic timer initialisation first */
for (unsigned i = 0; i < PWM_SERVO_MAX_TIMERS; i++) {
if (cfg->timers[i].base != 0)
pwm_timer_init(i);
}
/* now init channels */
for (unsigned i = 0; i < PWM_SERVO_MAX_CHANNELS; i++) {
if (cfg->channels[i].gpio != 0)
pwm_channel_init(i);
}
/* register the device */
return register_driver("/dev/pwm_servo", &pwm_servo_fops, 0666, NULL);
}
#endif /* CONFIG_PWM_SERVO */

View File

@ -0,0 +1,4 @@
/*
* There are no source files here, but libboard.a can't be empty, so
* we have this empty source file to keep it company.
*/

View File

@ -1,164 +0,0 @@
/************************************************************************************
* configs/stm3210e-eval/src/up_adc.c
* arch/arm/src/board/up_adc.c
*
* Copyright (C) 2011-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 <errno.h>
#include <debug.h>
#include <nuttx/analog/adc.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "stm32_pwm.h"
#include "px4io-internal.h"
#ifdef CONFIG_ADC
/************************************************************************************
* Definitions
************************************************************************************/
/* Configuration ********************************************************************/
/* Up to 3 ADC interfaces are supported */
#if STM32_NADC < 3
# undef CONFIG_STM32_ADC3
#endif
#if STM32_NADC < 2
# undef CONFIG_STM32_ADC2
#endif
#if STM32_NADC < 1
# undef CONFIG_STM32_ADC1
#endif
#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
#ifndef CONFIG_STM32_ADC1
# warning "Channel information only available for ADC1"
#endif
/* The number of ADC channels in the conversion list */
#define ADC1_NCHANNELS 2
/************************************************************************************
* Private Data
************************************************************************************/
/* Identifying number of each ADC channel: Variable Resistor */
#ifdef CONFIG_STM32_ADC1
static const uint8_t g_chanlist[ADC1_NCHANNELS] = {4, 5};
/* Configurations of pins used byte each ADC channels */
static const uint32_t g_pinlist[ADC1_NCHANNELS] = {GPIO_ADC1_IN4, GPIO_ADC1_IN5};
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: adc_devinit
*
* Description:
* All STM32 architectures must provide the following interface to work with
* examples/adc.
*
************************************************************************************/
int adc_devinit(void)
{
#ifdef CONFIG_STM32_ADC1
static bool initialized = false;
struct adc_dev_s *adc;
int ret;
int i;
/* Check if we have already initialized */
if (!initialized)
{
/* Configure the pins as analog inputs for the selected channels */
for (i = 0; i < ADC1_NCHANNELS; i++)
{
stm32_configgpio(g_pinlist[i]);
}
/* Call stm32_adcinitialize() to get an instance of the ADC interface */
adc = stm32_adcinitialize(1, g_chanlist, ADC1_NCHANNELS);
if (adc == NULL)
{
adbg("ERROR: Failed to get ADC interface\n");
return -ENODEV;
}
/* Register the ADC driver at "/dev/adc0" */
ret = adc_register("/dev/adc0", adc);
if (ret < 0)
{
adbg("adc_register failed: %d\n", ret);
return ret;
}
/* Now we are initialized */
initialized = true;
}
return OK;
#else
return -ENOSYS;
#endif
}
#endif /* CONFIG_STM32_ADC1 || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
#endif /* CONFIG_ADC */

View File

@ -1,178 +0,0 @@
/****************************************************************************
*
* 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 and configuration data.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <arch/board/board.h>
#include <arch/board/up_boardinitialize.h>
#include <arch/board/up_hrt.h>
#include <arch/board/drv_pwm_servo.h>
#include <arch/board/drv_gpio.h>
#include "chip.h"
#include "up_internal.h"
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32_gpio.h"
#include "stm32_tim.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Debug ********************************************************************/
/* Configuration ************************************************************/
#if CONFIG_PWM_SERVO
/*
* Servo configuration for the PX4IO board.
*/
static const struct pwm_servo_config servo_config = {
.update_rate = 50,
.timers = {
{
.base = STM32_TIM2_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM2EN,
.clock_freq = STM32_APB1_TIM2_CLKIN
},
{
.base = STM32_TIM3_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM3EN,
.clock_freq = STM32_APB1_TIM3_CLKIN
},
{
.base = STM32_TIM4_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM4EN,
.clock_freq = STM32_APB1_TIM4_CLKIN
},
},
.channels = {
{
.gpio = GPIO_TIM2_CH1OUT,
.timer_index = 0,
.timer_channel = 1,
.default_value = 1000,
},
{
.gpio = GPIO_TIM2_CH2OUT,
.timer_index = 0,
.timer_channel = 2,
.default_value = 1000,
},
{
.gpio = GPIO_TIM4_CH3OUT,
.timer_index = 2,
.timer_channel = 3,
.default_value = 1000,
},
{
.gpio = GPIO_TIM4_CH4OUT,
.timer_index = 2,
.timer_channel = 4,
.default_value = 1000,
},
{
.gpio = GPIO_TIM3_CH1OUT,
.timer_index = 1,
.timer_channel = 1,
.default_value = 1000,
},
{
.gpio = GPIO_TIM3_CH2OUT,
.timer_index = 1,
.timer_channel = 2,
.default_value = 1000,
},
{
.gpio = GPIO_TIM3_CH3OUT,
.timer_index = 1,
.timer_channel = 3,
.default_value = 1000,
},
{
.gpio = GPIO_TIM3_CH4OUT,
.timer_index = 1,
.timer_channel = 4,
.default_value = 1000,
},
}
};
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: nsh_archinitialize
*
* Description:
* Perform architecture specific initialization
*
****************************************************************************/
int up_boardinitialize()
{
/* configure the high-resolution time/callout interface */
#ifdef CONFIG_HRT_TIMER
hrt_init(CONFIG_HRT_TIMER);
#endif
/* configure the PWM servo driver */
#if CONFIG_PWM_SERVO
pwm_servo_init(&servo_config);
#endif
/* configure the GPIO driver */
gpio_drv_init();
return OK;
}

View File

@ -1,664 +0,0 @@
/****************************************************************************
*
* 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.
*
* This can use any general or advanced STM32 timer.
*
* Note that really, this could use systick too, but that's
* monopolised by NuttX and stealing it would just be awkward.
*
* We don't use the NuttX STM32 driver per se; rather, we
* claim the timer and then drive it directly.
*/
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <sys/types.h>
#include <stdbool.h>
#include <assert.h>
#include <debug.h>
#include <time.h>
#include <queue.h>
#include <errno.h>
#include <string.h>
#include <arch/board/board.h>
#include <arch/board/up_hrt.h>
#include "chip.h"
#include "up_internal.h"
#include "up_arch.h"
#include "stm32_internal.h"
#include "stm32_gpio.h"
#include "stm32_tim.h"
#ifdef CONFIG_HRT_TIMER
/* HRT configuration */
#if HRT_TIMER == 1
# define HRT_TIMER_BASE STM32_TIM1_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB2ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM1EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1CC
# define HRT_TIMER_CLOCK STM32_APB2_TIM1_CLKIN
# if CONFIG_STM32_TIM1
# error must not set CONFIG_STM32_TIM1=y and HRT_TIMER=1
# endif
#elif HRT_TIMER == 2
# define HRT_TIMER_BASE STM32_TIM2_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM2EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM2
# define HRT_TIMER_CLOCK STM32_APB1_TIM2_CLKIN
# if CONFIG_STM32_TIM2
# error must not set CONFIG_STM32_TIM2=y and HRT_TIMER=2
# endif
#elif HRT_TIMER == 3
# define HRT_TIMER_BASE STM32_TIM3_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM3EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM3
# define HRT_TIMER_CLOCK STM32_APB1_TIM3_CLKIN
# if CONFIG_STM32_TIM3
# error must not set CONFIG_STM32_TIM3=y and HRT_TIMER=3
# endif
#elif HRT_TIMER == 4
# define HRT_TIMER_BASE STM32_TIM4_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM4EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM4
# define HRT_TIMER_CLOCK STM32_APB1_TIM4_CLKIN
# if CONFIG_STM32_TIM4
# error must not set CONFIG_STM32_TIM4=y and HRT_TIMER=4
# endif
#elif HRT_TIMER == 5
# define HRT_TIMER_BASE STM32_TIM5_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM5EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM5
# define HRT_TIMER_CLOCK STM32_APB1_TIM5_CLKIN
# if CONFIG_STM32_TIM5
# error must not set CONFIG_STM32_TIM5=y and HRT_TIMER=5
# endif
#elif HRT_TIMER == 8
# define HRT_TIMER_BASE STM32_TIM8_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB2ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM8EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM8CC
# define HRT_TIMER_CLOCK STM32_APB2_TIM8_CLKIN
# if CONFIG_STM32_TIM8
# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=6
# endif
#elif HRT_TIMER == 9
# define HRT_TIMER_BASE STM32_TIM9_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM9EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1BRK
# define HRT_TIMER_CLOCK STM32_APB1_TIM9_CLKIN
# if CONFIG_STM32_TIM9
# error must not set CONFIG_STM32_TIM9=y and HRT_TIMER=9
# endif
#elif HRT_TIMER == 10
# define HRT_TIMER_BASE STM32_TIM10_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM10EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1UP
# define HRT_TIMER_CLOCK STM32_APB1_TIM10_CLKIN
# if CONFIG_STM32_TIM10
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=10
# endif
#elif HRT_TIMER == 11
# define HRT_TIMER_BASE STM32_TIM11_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM11EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1TRGCOM
# define HRT_TIMER_CLOCK STM32_APB1_TIM11_CLKIN
# if CONFIG_STM32_TIM11
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
# endif
#else
# error HRT_TIMER must be set in board.h if CONFIG_HRT_TIMER=y
#endif
/*
* HRT clock must be a multiple of 1MHz greater than 1MHz
*/
#if (HRT_TIMER_CLOCK % 1000000) != 0
# error HRT_TIMER_CLOCK must be a multiple of 1MHz
#endif
#if HRT_TIMER_CLOCK <= 1000000
# error HRT_TIMER_CLOCK must be greater than 1MHz
#endif
/*
* Minimum/maximum deadlines.
*
* These are suitable for use with a 16-bit timer/counter clocked
* at 1MHz. The high-resolution timer need only guarantee that it
* not wrap more than once in the 50ms period for absolute time to
* be consistently maintained.
*
* The minimum deadline must be such that the time taken between
* reading a time and writing a deadline to the timer cannot
* result in missing the deadline.
*/
#define HRT_INTERVAL_MIN 50
#define HRT_INTERVAL_MAX 50000
/*
* Period of the free-running counter, in microseconds.
*/
#define HRT_COUNTER_PERIOD 65536
/*
* Scaling factor(s) for the free-running counter; convert an input
* in counts to a time in microseconds.
*/
#define HRT_COUNTER_SCALE(_c) (_c)
/*
* Timer register accessors
*/
#define REG(_reg) (*(volatile uint32_t *)(HRT_TIMER_BASE + _reg))
#define rCR1 REG(STM32_GTIM_CR1_OFFSET)
#define rCR2 REG(STM32_GTIM_CR2_OFFSET)
#define rSMCR REG(STM32_GTIM_SMCR_OFFSET)
#define rDIER REG(STM32_GTIM_DIER_OFFSET)
#define rSR REG(STM32_GTIM_SR_OFFSET)
#define rEGR REG(STM32_GTIM_EGR_OFFSET)
#define rCCMR1 REG(STM32_GTIM_CCMR1_OFFSET)
#define rCCMR2 REG(STM32_GTIM_CCMR2_OFFSET)
#define rCCER REG(STM32_GTIM_CCER_OFFSET)
#define rCNT REG(STM32_GTIM_CNT_OFFSET)
#define rPSC REG(STM32_GTIM_PSC_OFFSET)
#define rARR REG(STM32_GTIM_ARR_OFFSET)
#define rCCR1 REG(STM32_GTIM_CCR1_OFFSET)
#define rCCR2 REG(STM32_GTIM_CCR2_OFFSET)
#define rCCR3 REG(STM32_GTIM_CCR3_OFFSET)
#define rCCR4 REG(STM32_GTIM_CCR4_OFFSET)
#define rDCR REG(STM32_GTIM_DCR_OFFSET)
#define rDMAR REG(STM32_GTIM_DMAR_OFFSET)
/*
* Specific registers and bits used by HRT sub-functions
*/
#if HRT_TIMER_CHANNEL == 1
# define rCCR_HRT rCCR1 /* compare register for HRT */
# define DIER_HRT GTIM_DIER_CC1IE /* interrupt enable for HRT */
# define SR_INT_HRT GTIM_SR_CC1IF /* interrupt status for HRT */
#elif HRT_TIMER_CHANNEL == 2
# define rCCR_HRT rCCR2 /* compare register for HRT */
# define DIER_HRT GTIM_DIER_CC2IE /* interrupt enable for HRT */
# define SR_INT_HRT GTIM_SR_CC2IF /* interrupt status for HRT */
#elif HRT_TIMER_CHANNEL == 3
# define rCCR_HRT rCCR3 /* compare register for HRT */
# define DIER_HRT GTIM_DIER_CC3IE /* interrupt enable for HRT */
# define SR_INT_HRT GTIM_SR_CC3IF /* interrupt status for HRT */
#elif HRT_TIMER_CHANNEL == 4
# define rCCR_HRT rCCR4 /* compare register for HRT */
# define DIER_HRT GTIM_DIER_CC4IE /* interrupt enable for HRT */
# define SR_INT_HRT GTIM_SR_CC4IF /* interrupt status for HRT */
#else
# error HRT_TIMER_CHANNEL must be a value between 1 and 4
#endif
/*
* Queue of callout entries.
*/
static struct sq_queue_s callout_queue;
/*
* The time corresponding to a counter value of zero, as of the
* last time that hrt_absolute_time() was called.
*/
static hrt_abstime base_time;
/* timer-specific functions */
static void hrt_tim_init(int timer);
static int hrt_tim_isr(int irq, void *context);
/* callout list manipulation */
static void hrt_call_enter(struct hrt_call *entry);
static void hrt_call_reschedule(void);
static void hrt_call_invoke(void);
/*
* Specific registers and bits used by PPM sub-functions
*/
#ifdef CONFIG_HRT_PPM
# include <arch/board/drv_ppm_input.h>
/*
* If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it.
*/
# ifndef GTIM_CCER_CC1NP
# define GTIM_CCER_CC1NP 0
# define GTIM_CCER_CC2NP 0
# define GTIM_CCER_CC3NP 0
# define GTIM_CCER_CC4NP 0
# define PPM_EDGE_FLIP
# endif
# if HRT_PPM_CHANNEL == 1
# define rCCR_PPM rCCR1 /* capture register for PPM */
# define DIER_PPM GTIM_DIER_CC1IE /* capture interrupt (non-DMA mode) */
# define SR_INT_PPM GTIM_SR_CC1IF /* capture interrupt (non-DMA mode) */
# define SR_OVF_PPM GTIM_SR_CC1OF /* capture overflow (non-DMA mode) */
# define CCMR1_PPM 1 /* on TI1 */
# define CCMR2_PPM 0
# define CCER_PPM (GTIM_CCER_CC1E | GTIM_CCER_CC1P | GTIM_CCER_CC1NP) /* CC1, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC1P
# elif HRT_PPM_CHANNEL == 2
# define rCCR_PPM rCCR2 /* capture register for PPM */
# define DIER_PPM GTIM_DIER_CC2IE /* capture interrupt (non-DMA mode) */
# define SR_INT_PPM GTIM_SR_CC2IF /* capture interrupt (non-DMA mode) */
# define SR_OVF_PPM GTIM_SR_CC2OF /* capture overflow (non-DMA mode) */
# define CCMR1_PPM 2 /* on TI2 */
# define CCMR2_PPM 0
# define CCER_PPM (GTIM_CCER_CC2E | GTIM_CCER_CC2P | GTIM_CCER_CC2NP) /* CC2, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC2P
# elif HRT_PPM_CHANNEL == 3
# define rCCR_PPM rCCR3 /* capture register for PPM */
# define DIER_PPM GTIM_DIER_CC3IE /* capture interrupt (non-DMA mode) */
# define SR_INT_PPM GTIM_SR_CC3IF /* capture interrupt (non-DMA mode) */
# define SR_OVF_PPM GTIM_SR_CC3OF /* capture overflow (non-DMA mode) */
# define CCMR1_PPM 0
# define CCMR2_PPM 1 /* on TI3 */
# define CCER_PPM (GTIM_CCER_CC3E | GTIM_CCER_CC3P | GTIM_CCER_CC3NP) /* CC3, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC3P
# elif HRT_PPM_CHANNEL == 4
# define rCCR_PPM rCCR4 /* capture register for PPM */
# define DIER_PPM GTIM_DIER_CC4IE /* capture interrupt (non-DMA mode) */
# define SR_INT_PPM GTIM_SR_CC4IF /* capture interrupt (non-DMA mode) */
# define SR_OVF_PPM GTIM_SR_CC4OF /* capture overflow (non-DMA mode) */
# define CCMR1_PPM 0
# define CCMR2_PPM 2 /* on TI4 */
# define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC4P
# else
# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set
# endif
#else
/* disable the PPM configuration */
# define rCCR_PPM 0
# define DIER_PPM 0
# define SR_INT_PPM 0
# define SR_OVF_PPM 0
# define CCMR1_PPM 0
# define CCMR2_PPM 0
# define CCER_PPM 0
#endif /* CONFIG_HRT_PPM */
/*
* Initialise the timer we are going to use.
*
* We expect that we'll own one of the reduced-function STM32 general
* timers, and that we can use channel 1 in compare mode.
*/
static void
hrt_tim_init(int timer)
{
/* clock/power on our timer */
modifyreg32(HRT_TIMER_POWER_REG, 0, HRT_TIMER_POWER_BIT);
/* claim our interrupt vector */
irq_attach(HRT_TIMER_VECTOR, hrt_tim_isr);
/* disable and configure the timer */
rCR1 = 0;
rCR2 = 0;
rSMCR = 0;
rDIER = DIER_HRT | DIER_PPM;
rCCER = 0; /* unlock CCMR* registers */
rCCMR1 = CCMR1_PPM;
rCCMR2 = CCMR2_PPM;
rCCER = CCER_PPM;
rDCR = 0;
/* configure the timer to free-run at 1MHz */
rPSC = (HRT_TIMER_CLOCK / 1000000) - 1; /* this really only works for whole-MHz clocks */
/* run the full span of the counter */
rARR = 0xffff;
/* set an initial capture a little ways off */
rCCR_HRT = 1000;
/* generate an update event; reloads the counter, all registers */
rEGR = GTIM_EGR_UG;
/* enable the timer */
rCR1 = GTIM_CR1_CEN;
/* enable interrupts */
up_enable_irq(HRT_TIMER_VECTOR);
}
/*
* Handle the compare interupt by calling the callout dispatcher
* and then re-scheduling the next deadline.
*/
static int
hrt_tim_isr(int irq, void *context)
{
uint32_t status;
/* copy interrupt status */
status = rSR;
/* ack the interrupts we just read */
rSR = ~status;
#ifdef CONFIG_HRT_PPM
/* was this a PPM edge? */
if (status & (SR_INT_PPM | SR_OVF_PPM)) {
/* if required, flip edge sensitivity */
# ifdef PPM_EDGE_FLIP
rCCER ^= CCER_PPM_FLIP;
# endif
/* feed the edge to the PPM decoder */
ppm_input_decode(status & SR_OVF_PPM, rCCR_PPM);
}
#endif
/* was this a timer tick? */
if (status & SR_INT_HRT) {
/* run any callouts that have met their deadline */
hrt_call_invoke();
/* and schedule the next interrupt */
hrt_call_reschedule();
}
return OK;
}
/*
* Fetch a never-wrapping absolute time value in microseconds from
* some arbitrary epoch shortly after system start.
*/
hrt_abstime
hrt_absolute_time(void)
{
static uint32_t last_count;
uint32_t count;
uint32_t flags = irqsave();
count = rCNT;
//lldbg("count %u last_count %u\n", count, last_count);
/* This simple test is made possible by the guarantee that
* we are always called at least once per counter period.
*/
if (count < last_count)
base_time += HRT_COUNTER_PERIOD;
last_count = count;
irqrestore(flags);
return HRT_COUNTER_SCALE(base_time + count);
}
/*
* Convert a timespec to absolute time
*/
hrt_abstime
ts_to_abstime(struct timespec *ts)
{
hrt_abstime result;
result = (hrt_abstime)(ts->tv_sec) * 1000000;
result += ts->tv_nsec / 1000;
return result;
}
/*
* Convert absolute time to a timespec.
*/
void
abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
{
ts->tv_sec = abstime / 1000000;
abstime -= ts->tv_sec * 1000000;
ts->tv_nsec = abstime * 1000;
}
/*
* Initalise the high-resolution timing module.
*/
void
hrt_init(int timer)
{
sq_init(&callout_queue);
hrt_tim_init(timer);
}
/*
* Call callout(arg) after interval has elapsed.
*/
void
hrt_call_after(struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, void *arg)
{
entry->deadline = hrt_absolute_time() + delay;
entry->period = 0;
entry->callout = callout;
entry->arg = arg;
hrt_call_enter(entry);
}
/*
* Call callout(arg) at calltime.
*/
void
hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, void *arg)
{
entry->deadline = calltime;
entry->period = 0;
entry->callout = callout;
entry->arg = arg;
hrt_call_enter(entry);
}
/*
* Call callout(arg) every period.
*/
void
hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg)
{
entry->deadline = hrt_absolute_time() + delay;
entry->period = interval;
entry->callout = callout;
entry->arg = arg;
hrt_call_enter(entry);
}
/*
* If this returns true, the call has been invoked and removed from the callout list.
*
* Always returns false for repeating callouts.
*/
bool
hrt_called(struct hrt_call *entry)
{
bool result;
irqstate_t flags = irqsave();
result = (entry->deadline == 0);
irqrestore(flags);
return result;
}
/*
* Remove the entry from the callout list.
*/
void
hrt_cancel(struct hrt_call *entry)
{
irqstate_t flags = irqsave();
sq_rem(&entry->link, &callout_queue);
entry->deadline = 0;
/* if this is a periodic call being removed by the callout, prevent it from
* being re-entered when the callout returns.
*/
entry->period = 0;
irqrestore(flags);
}
static void
hrt_call_enter(struct hrt_call *entry)
{
irqstate_t flags = irqsave();
struct hrt_call *call, *next;
call = (struct hrt_call *)sq_peek(&callout_queue);
if ((call == NULL) || (entry->deadline < call->deadline)) {
sq_addfirst(&entry->link, &callout_queue);
//lldbg("call enter at head, reschedule\n");
/* we changed the next deadline, reschedule the timer event */
hrt_call_reschedule();
} else {
do {
next = (struct hrt_call *)sq_next(&call->link);
if ((next == NULL) || (entry->deadline < next->deadline)) {
//lldbg("call enter after head\n");
sq_addafter(&call->link, &entry->link, &callout_queue);
break;
}
} while ((call = next) != NULL);
}
//lldbg("scheduled\n");
irqrestore(flags);
}
static void
hrt_call_invoke(void)
{
struct hrt_call *call;
hrt_abstime deadline;
while (true) {
/* get the current time */
hrt_abstime now = hrt_absolute_time();
call = (struct hrt_call *)sq_peek(&callout_queue);
if (call == NULL)
break;
if (call->deadline > now)
break;
sq_rem(&call->link, &callout_queue);
//lldbg("call pop\n");
/* save the intended deadline for periodic calls */
deadline = call->deadline;
/* zero the deadline, as the call has occurred */
call->deadline = 0;
/* invoke the callout (if there is one) */
if (call->callout) {
//lldbg("call %p: %p(%p)\n", call, call->callout, call->arg);
call->callout(call->arg);
}
/* if the callout has a non-zero period, it has to be re-entered */
if (call->period != 0) {
call->deadline = deadline + call->period;
hrt_call_enter(call);
}
}
}
/*
* Reschedule the next timer interrupt.
*
* This routine must be called with interrupts disabled.
*/
static void
hrt_call_reschedule()
{
hrt_abstime now = hrt_absolute_time();
struct hrt_call *next = (struct hrt_call *)sq_peek(&callout_queue);
hrt_abstime deadline = now + HRT_INTERVAL_MAX;
/*
* Determine what the next deadline will be.
*
* Note that we ensure that this will be within the counter
* period, so that when we truncate all but the low 16 bits
* the next time the compare matches it will be the deadline
* we want.
*
* It is important for accurate timekeeping that the compare
* interrupt fires sufficiently often that the base_time update in
* hrt_absolute_time runs at least once per timer period.
*/
if (next != NULL) {
//lldbg("entry in queue\n");
if (next->deadline <= (now + HRT_INTERVAL_MIN)) {
//lldbg("pre-expired\n");
/* set a minimal deadline so that we call ASAP */
deadline = now + HRT_INTERVAL_MIN;
} else if (next->deadline < deadline) {
//lldbg("due soon\n");
deadline = next->deadline;
}
}
//lldbg("schedule for %u at %u\n", (unsigned)(deadline & 0xffffffff), (unsigned)(now & 0xffffffff));
/* set the new compare value */
rCCR_HRT = deadline & 0xffff;
}
#endif /* CONFIG_HRT_TIMER */

View File

@ -1,63 +0,0 @@
/****************************************************************************
* config/stm3210e_eval/src/up_nsh.c
* arch/arm/src/board/up_nsh.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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 <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include "stm32_internal.h"
#include <arch/board/up_boardinitialize.h>
/****************************************************************************
* Name: nsh_archinitialize
*
* Description:
* Perform architecture specific initialization
*
****************************************************************************/
int nsh_archinitialize(void)
{
return up_boardinitialize();
}