nxp/fmuk66-v3: use hw description methods for timer configuration

This commit is contained in:
Beat Küng 2020-01-03 10:34:49 +01:00 committed by David Sidrane
parent 5319a98fec
commit c01f6811d0
6 changed files with 28 additions and 165 deletions

View File

@ -305,34 +305,6 @@
#define PIN_I2C1_SDA PIN_I2C1_SDA_1 /* PTC11 GPS / Pressure Sensor */
/* PWM
*
*/
/* PWM Channels */
#define GPIO_FTM0_CH0OUT PIN_FTM0_CH0_2 /* PTC1 FMU_CH1 P4-19 */
#define GPIO_FTM0_CH3OUT PIN_FTM0_CH3_1 /* PTA6 FMU_CH2 P4-16 */
#define GPIO_FTM0_CH4OUT PIN_FTM0_CH4_3 /* PTD4 FMU_CH3 P4-13 */
#define GPIO_FTM0_CH5OUT PIN_FTM0_CH5_3 /* PTD5 FMU_CH4 P4-10 */
#define GPIO_FTM3_CH6OUT PIN_FTM3_CH6_2 /* PTE11 FMU_CH5 P4-7 */
#define GPIO_FTM3_CH7OUT PIN_FTM3_CH7_2 /* PTE12 FMU_CH5 P4-4 */
#define GPIO_FTM3_CH0OUT PIN_FTM3_CH0_1 /* PTD0 U_TRI P10-2 */
#define GPIO_FTM2_CH0OUT PIN_FTM2_CH0_1 /* PTA10 U_ECH P20-3 */
#define GPIO_FTM0_CH0IN PIN_FTM0_CH0_2 /* PTC1 FMU_CH1 P4-19 */
#define GPIO_FTM0_CH3IN PIN_FTM0_CH3_1 /* PTA6 FMU_CH2 P4-16 */
#define GPIO_FTM0_CH4IN PIN_FTM0_CH4_3 /* PTD4 FMU_CH3 P4-13 */
#define GPIO_FTM0_CH5IN PIN_FTM0_CH5_3 /* PTD5 FMU_CH4 P4-10 */
#define GPIO_FTM3_CH6IN PIN_FTM3_CH6_2 /* PTE11 FMU_CH5 P4-7 */
#define GPIO_FTM3_CH7IN PIN_FTM3_CH7_2 /* PTE12 FMU_CH5 P4-4 */
#define GPIO_FTM3_CH0IN PIN_FTM3_CH0_1 /* PTD0 U_TRI P10-2 */
#define GPIO_FTM2_CH0IN PIN_FTM2_CH0_1 /* PTA10 U_ECH P20-3 */
/* SPI
*
*/

View File

@ -39,7 +39,7 @@ add_library(drivers_board
led.c
sdhc.c
spi.c
timer_config.c
timer_config.cpp
usb.c
)

View File

@ -320,41 +320,8 @@ __BEGIN_DECLS
/* User GPIOs
*
* GPIO-
* Define as GPIO input / GPIO outputs and timers IO
*/
#define PX4_MK_GPIO(pin_ftmx, io) ((((uint32_t)(pin_ftmx)) & ~(_PIN_MODE_MASK | _PIN_OPTIONS_MASK)) |(io))
#define PX4_MK_GPIO_INPUT(pin_ftmx) PX4_MK_GPIO(pin_ftmx, GPIO_PULLUP)
#define PX4_MK_GPIO_OUTPUT(pin_ftmx) PX4_MK_GPIO(pin_ftmx, GPIO_HIGHDRIVE)
#define GPIO_GPIO0_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH0OUT) /* FMU_CH1 */
#define GPIO_GPIO1_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH3OUT) /* FMU_CH2 */
#define GPIO_GPIO2_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH4OUT) /* FMU_CH3 */
#define GPIO_GPIO3_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH5OUT) /* FMU_CH4 */
#define GPIO_GPIO4_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH6OUT) /* FMU_CH5 */
#define GPIO_GPIO5_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH7OUT) /* FMU_CH6 */
#define GPIO_GPIO6_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH0OUT) /* U_TRI */
#define GPIO_GPIO7_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM2_CH0OUT) /* U_ECHO */
#define GPIO_GPIO0_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH0OUT) /* FMU_CH1 */
#define GPIO_GPIO1_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH3OUT) /* FMU_CH2 */
#define GPIO_GPIO2_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH4OUT) /* FMU_CH3 */
#define GPIO_GPIO3_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH5OUT) /* FMU_CH4 */
#define GPIO_GPIO4_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH6OUT) /* FMU_CH5 */
#define GPIO_GPIO5_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH7OUT) /* FMU_CH6 */
#define GPIO_GPIO6_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH0OUT) /* U_TRI */
#define GPIO_GPIO7_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM2_CH0OUT) /* U_ECHO */
/* P13 Ultrasonic Sensors
* Timer Capture driver the the Trigger and sample the response on Echo
*/
#define GPIO_TRI GPIO_GPIO6_OUTPUT
#define GPIO_ECH GPIO_GPIO7_INPUT
/* Timer I/O PWM and capture
*
* 14 PWM outputs are configured.
@ -439,16 +406,6 @@ __BEGIN_DECLS
#define BOARD_HAS_ON_RESET 1
#define PX4_GPIO_PWM_INIT_LIST { \
GPIO_GPIO5_INPUT, \
GPIO_GPIO4_INPUT, \
GPIO_GPIO3_INPUT, \
GPIO_GPIO2_INPUT, \
GPIO_GPIO1_INPUT, \
GPIO_GPIO0_INPUT, \
GPIO_TRI, \
}
#define PX4_GPIO_INIT_LIST { \
GPIO_LED_R, \
GPIO_LED_G, \
@ -461,7 +418,6 @@ __BEGIN_DECLS
GPIO_GM_nRST, \
GPIO_A_RST, \
GPIO_USB_VBUS_VALID, \
GPIO_ECH, \
GPIO_ENET_RST, \
GPIO_ENET_EN, \
GPIO_ENET_INH, \

View File

@ -74,6 +74,7 @@
#include <systemlib/px4_macros.h>
#include <px4_arch/io_timer.h>
#include <px4_platform_common/init.h>
#include <px4_platform/board_dma_alloc.h>
@ -114,10 +115,12 @@ __END_DECLS
void board_on_reset(int status)
{
/* configure the GPIO pins to outputs and keep them low */
for (int i = 0; i < 6; ++i) {
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i)));
}
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
px4_arch_configgpio(io_timer_channel_get_gpio_output(6)); // Echo trigger pin
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(7)));
if (status >= 0) {
up_mdelay(6);

View File

@ -55,6 +55,8 @@
#if defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI1) || defined(CONFIG_KINETIS_SPI2)
#define PX4_MK_GPIO(pin_ftmx, io) ((((uint32_t)(pin_ftmx)) & ~(_PIN_MODE_MASK | _PIN_OPTIONS_MASK)) |(io))
/* Define CS GPIO array */
static const uint32_t spi0selects_gpio[] = PX4_MEMORY_BUS_CS_GPIO;
static const uint32_t spi1selects_gpio[] = PX4_SENSOR_BUS_CS_GPIO;

View File

@ -47,101 +47,31 @@
#include "hardware/kinetis_ftm.h"
#include <drivers/drv_pwm_output.h>
#include <px4_arch/io_timer.h>
#include <px4_arch/io_timer_hw_description.h>
#include "board_config.h"
__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
{
.base = KINETIS_FTM0_BASE,
.clock_register = KINETIS_SIM_SCGC6,
.clock_bit = SIM_SCGC6_FTM0,
.vectorno = KINETIS_IRQ_FTM0,
},
{
.base = KINETIS_FTM3_BASE,
.clock_register = KINETIS_SIM_SCGC3,
.clock_bit = SIM_SCGC3_FTM3,
.vectorno = KINETIS_IRQ_FTM3,
},
{
.base = KINETIS_FTM2_BASE,
.clock_register = KINETIS_SIM_SCGC3,
.clock_bit = SIM_SCGC3_FTM2,
.vectorno = KINETIS_IRQ_FTM2,
}
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::FTM0),
initIOTimer(Timer::FTM3),
initIOTimer(Timer::FTM2),
};
__EXPORT const io_timers_channel_mapping_t io_timers_channel_mapping = {
.element = {
{
.first_channel_index = 0,
.channel_count = 4,
},
{
.first_channel_index = 4,
.channel_count = 3,
},
{
.first_channel_index = 6,
.channel_count = 1,
}
}
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel0}, {GPIO::PortC, GPIO::Pin1}),
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel3}, {GPIO::PortA, GPIO::Pin6}),
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel4}, {GPIO::PortD, GPIO::Pin4}),
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel5}, {GPIO::PortD, GPIO::Pin5}),
initIOTimerChannel(io_timers, {Timer::FTM3, Timer::Channel6}, {GPIO::PortE, GPIO::Pin11}),
initIOTimerChannel(io_timers, {Timer::FTM3, Timer::Channel7}, {GPIO::PortE, GPIO::Pin12}),
initIOTimerChannel(io_timers, {Timer::FTM3, Timer::Channel0}, {GPIO::PortD, GPIO::Pin0}),
initIOTimerChannel(io_timers, {Timer::FTM2, Timer::Channel0}, {GPIO::PortA, GPIO::Pin10}),
};
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
{
.gpio_out = GPIO_FTM0_CH0OUT, // FMU_CH1
.gpio_in = GPIO_FTM0_CH0IN,
.timer_index = 0,
.timer_channel = 1, // physical channel number +1
},
{
.gpio_out = GPIO_FTM0_CH3OUT, // FMU_CH2
.gpio_in = GPIO_FTM0_CH3IN,
.timer_index = 0,
.timer_channel = 4,
},
{
.gpio_out = GPIO_FTM0_CH4OUT, // FMU_CH3
.gpio_in = GPIO_FTM0_CH4IN,
.timer_index = 0,
.timer_channel = 5,
},
{
.gpio_out = GPIO_FTM0_CH5OUT, // FMU_CH4
.gpio_in = GPIO_FTM0_CH5IN,
.timer_index = 0,
.timer_channel = 6,
},
{
.gpio_out = GPIO_FTM3_CH6OUT, // FMU_CH5
.gpio_in = GPIO_FTM3_CH6IN,
.timer_index = 1,
.timer_channel = 7,
},
{
.gpio_out = GPIO_FTM3_CH7OUT, // FMU_CH6
.gpio_in = GPIO_FTM3_CH7IN,
.timer_index = 1,
.timer_channel = 8,
},
{
.gpio_out = GPIO_FTM3_CH0OUT, // U_TRI
.gpio_in = GPIO_FTM3_CH0IN,
.timer_index = 1,
.timer_channel = 1,
},
{
.gpio_out = GPIO_FTM2_CH0OUT,
.gpio_in = GPIO_FTM2_CH0IN, // U_ECH
.timer_index = 2,
.timer_channel = 1,
},
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);
__EXPORT const struct io_timers_t led_pwm_timers[MAX_LED_TIMERS] = {
const struct io_timers_t led_pwm_timers[MAX_LED_TIMERS] = {
{
.base = KINETIS_FTM3_BASE,
.clock_register = KINETIS_SIM_SCGC3,
@ -150,7 +80,7 @@ __EXPORT const struct io_timers_t led_pwm_timers[MAX_LED_TIMERS] = {
},
};
__EXPORT const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
{
.gpio_out = LED_TIM3_CH1OUT, // RGB_R
.gpio_in = 0,
@ -223,7 +153,7 @@ __EXPORT const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNEL
#endif
__EXPORT void fmuk66_timer_initialize(void)
void fmuk66_timer_initialize(void)
{