Browse Source

Added pwm_trigger from master

sbg
David Sidrane 8 years ago committed by Daniel Agar
parent
commit
bc4102bf3f
  1. 3
      src/drivers/kinetis/CMakeLists.txt
  2. 15
      src/drivers/kinetis/drv_io_timer.h
  3. 108
      src/drivers/kinetis/drv_pwm_trigger.c
  4. 42
      src/drivers/kinetis/drv_pwm_trigger.h

3
src/drivers/kinetis/CMakeLists.txt

@ -1,6 +1,6 @@
############################################################################ ############################################################################
# #
# Copyright (c) 2016 PX4 Development Team. All rights reserved. # Copyright (c) 2016-2017 PX4 Development Team. All rights reserved.
# #
# Redistribution and use in source and binary forms, with or without # Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions # modification, are permitted provided that the following conditions
@ -37,6 +37,7 @@ px4_add_module(
drv_hrt.c drv_hrt.c
drv_io_timer.c drv_io_timer.c
drv_pwm_servo.c drv_pwm_servo.c
drv_pwm_trigger.c
drv_input_capture.c drv_input_capture.c
drv_led_pwm.cpp drv_led_pwm.cpp
DEPENDS DEPENDS

15
src/drivers/kinetis/drv_io_timer.h

@ -1,6 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (C) 2012 PX4 Development Team. All rights reserved. * Copyright (C) 2012, 2017 PX4 Development Team. All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -48,8 +48,8 @@ __BEGIN_DECLS
#define MAX_IO_TIMERS 4 #define MAX_IO_TIMERS 4
#define MAX_TIMER_IO_CHANNELS 8 #define MAX_TIMER_IO_CHANNELS 8
#define MAX_LED_TIMERS 1 #define MAX_LED_TIMERS 2
#define MAX_TIMER_LED_CHANNELS 3 #define MAX_TIMER_LED_CHANNELS 6
#define IO_TIMER_ALL_MODES_CHANNELS 0 #define IO_TIMER_ALL_MODES_CHANNELS 0
@ -59,6 +59,7 @@ typedef enum io_timer_channel_mode_t {
IOTimerChanMode_PWMIn = 2, IOTimerChanMode_PWMIn = 2,
IOTimerChanMode_Capture = 3, IOTimerChanMode_Capture = 3,
IOTimerChanMode_OneShot = 4, IOTimerChanMode_OneShot = 4,
IOTimerChanMode_Trigger = 5,
IOTimerChanModeSize IOTimerChanModeSize
} io_timer_channel_mode_t; } io_timer_channel_mode_t;
@ -107,10 +108,10 @@ __EXPORT extern const io_timers_t led_pwm_timers[MAX_LED_TIMERS];
__EXPORT extern const timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS]; __EXPORT extern const timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS];
__EXPORT extern io_timer_channel_allocation_t allocations[IOTimerChanModeSize]; __EXPORT extern io_timer_channel_allocation_t allocations[IOTimerChanModeSize];
__EXPORT int io_timer_handler0(int irq, void *context, void *args); __EXPORT int io_timer_handler0(int irq, void *context, void *arg);
__EXPORT int io_timer_handler1(int irq, void *context, void *args); __EXPORT int io_timer_handler1(int irq, void *context, void *arg);
__EXPORT int io_timer_handler2(int irq, void *context, void *args); __EXPORT int io_timer_handler2(int irq, void *context, void *arg);
__EXPORT int io_timer_handler3(int irq, void *context, void *args); __EXPORT int io_timer_handler3(int irq, void *context, void *arg);
__EXPORT int io_timer_channel_init(unsigned channel, io_timer_channel_mode_t mode, __EXPORT int io_timer_channel_init(unsigned channel, io_timer_channel_mode_t mode,
channel_handler_t channel_handler, void *context); channel_handler_t channel_handler, void *context);

108
src/drivers/kinetis/drv_pwm_trigger.c

@ -0,0 +1,108 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file drv_pwm_trigger.c
*
*/
#include <px4_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 <arch/board/board.h>
#include <drivers/drv_pwm_trigger.h>
#include "drv_io_timer.h"
#include "drv_pwm_trigger.h"
int up_pwm_trigger_set(unsigned channel, uint16_t value)
{
return io_timer_set_ccr(channel, value);
}
int up_pwm_trigger_init(uint32_t channel_mask)
{
/* Init channels */
for (unsigned channel = 0; channel_mask != 0 && channel < MAX_TIMER_IO_CHANNELS; channel++) {
if (channel_mask & (1 << channel)) {
// First free any that were not trigger mode before
if (-EBUSY == io_timer_is_channel_free(channel)) {
io_timer_free_channel(channel);
}
io_timer_channel_init(channel, IOTimerChanMode_Trigger, NULL, NULL);
channel_mask &= ~(1 << channel);
}
}
/* Enable the timers */
up_pwm_trigger_arm(true);
return OK;
}
void up_pwm_trigger_deinit()
{
/* Disable the timers */
up_pwm_trigger_arm(false);
/* Deinit channels */
uint32_t current = io_timer_get_mode_channels(IOTimerChanMode_Trigger);
for (unsigned channel = 0; current != 0 && channel < MAX_TIMER_IO_CHANNELS; channel++) {
if (current & (1 << channel)) {
io_timer_channel_init(channel, IOTimerChanMode_NotUsed, NULL, NULL);
current &= ~(1 << channel);
}
}
}
void
up_pwm_trigger_arm(bool armed)
{
io_timer_set_enable(armed, IOTimerChanMode_Trigger, IO_TIMER_ALL_MODES_CHANNELS);
}

42
src/drivers/kinetis/drv_pwm_trigger.h

@ -0,0 +1,42 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file drv_pwm_trigger.h
*
* stm32-specific PWM output data.
*/
#pragma once
#include <drivers/drv_pwm_trigger.h>
Loading…
Cancel
Save