Skip to content

Commit

Permalink
crazyflie: use hw description methods for timer configuration
Browse files Browse the repository at this point in the history
  • Loading branch information
bkueng committed Jan 6, 2020
1 parent 11d50b2 commit 4d609bd
Show file tree
Hide file tree
Showing 4 changed files with 64 additions and 149 deletions.
2 changes: 1 addition & 1 deletion boards/bitcraze/crazyflie/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ add_library(drivers_board
init.c
led.c
spi.c
timer_config.c
timer_config.cpp
usb.c
)
target_link_libraries(drivers_board
Expand Down
19 changes: 0 additions & 19 deletions boards/bitcraze/crazyflie/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -161,29 +161,10 @@
#define GPIO_TONE_ALARM_NEG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)

/* PWM
*
* Four PWM motor outputs are configured.
*
* Pins:
*
* CH1 : PA1 : TIM2_CH2
* CH2 : PB11 : TIM2_CH4
* CH3 : PA15 : TIM2_CH1
* CH4 : PB9 : TIM4_CH4
*/

#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1
#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_2
#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_2
#define GPIO_TIM4_CH4OUT GPIO_TIM4_CH4OUT_1
#define DIRECT_PWM_OUTPUT_CHANNELS 4

#define GPIO_TIM2_CH2IN GPIO_TIM2_CH2IN_1
#define GPIO_TIM2_CH4IN GPIO_TIM2_CH4IN_2
#define GPIO_TIM2_CH1IN GPIO_TIM2_CH1IN_2
#define GPIO_TIM4_CH4IN GPIO_TIM4_CH4IN_1


/* This board overrides the defaults by providing
* PX4_PWM_ALTERNATE_RANGES and a replacement set of
* constants
Expand Down
129 changes: 0 additions & 129 deletions boards/bitcraze/crazyflie/src/timer_config.c

This file was deleted.

63 changes: 63 additions & 0 deletions boards/bitcraze/crazyflie/src/timer_config.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
/****************************************************************************
*
* Copyright (C) 2016 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.
*
****************************************************************************/

#include <px4_arch/io_timer_hw_description.h>

/* IO Timers normally free-run at 1MHz
* Here we make adjustments to the Frequency that sets the timer's prescale
* so that the prescale is set to 0
*/
#define TIMx_CLKIN 1000000

static inline constexpr io_timers_t initIOTimerOverrideClockFreq(Timer::Timer timer)
{
io_timers_t ret = initIOTimer(timer);
ret.clock_freq = TIMx_CLKIN;
return ret;
}

__EXPORT constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimerOverrideClockFreq(Timer::Timer2),
initIOTimerOverrideClockFreq(Timer::Timer4),
};

// FIXME: this is incorrect, TIM2 channels are not all grouped together
__EXPORT constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}),
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel1}, {GPIO::PortA, GPIO::Pin15}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortB, GPIO::Pin9}),
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortB, GPIO::Pin11}),
};

__EXPORT constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);

0 comments on commit 4d609bd

Please sign in to comment.