Skip to content
This repository has been archived by the owner on Oct 1, 2021. It is now read-only.

DMA based bitbanging level interface #79

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion Tools/px_romfs_pruner.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ def main():
for (root, dirs, files) in os.walk(args.folder):
for file in files:
# only prune text files
if ".zip" in file or ".bin" in file or ".swp" in file \
if ".zip" in file or ".bin" in file or ".ledbin" in file or ".swp" in file \
or ".data" in file or ".DS_Store" in file \
or file.startswith("."):
continue
Expand Down
2 changes: 1 addition & 1 deletion nuttx-configs/px4fmu-v2/include/board.h
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@

/* UART RX DMA configurations */
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1

/*
* CAN
Expand Down
12 changes: 10 additions & 2 deletions src/drivers/boards/px4fmu-v2/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ __BEGIN_DECLS
#define PX4IO_SERIAL_BASE STM32_USART6_BASE /* hardwired on the board */
#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX_2
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX_2
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX_1
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */

Expand Down Expand Up @@ -228,14 +228,22 @@ __BEGIN_DECLS
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)

/* High-resolution timer */
#define HRT_TIMER 8 /* use timer8 for the HRT */
#define HRT_TIMER 5 /* use timer5 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */

/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
#define PWMIN_TIMER 4
#define PWMIN_TIMER_CHANNEL 2
#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2

/* Extra Purpose DMA */
//Note: Only DMA2 has access to AHB bus meaning GPIO registers are only modifiable by DMA2,
//refer DMA section of stm32F4 series User manual for further details.
#define DMAMAP_BITBANG STM32_DMA_MAP(DMA2,DMA_STREAM2,DMA_CHAN7)
#define TIMER_BITBANG 8
// Refer manual for DMA Request map to select proper timer channel
#define TIMER_BITBANG_CH 1
#define BITBANG_GPIO_REG_BASE STM32_GPIOD_BASE
/****************************************************************************************************
* Public Types
****************************************************************************************************/
Expand Down
62 changes: 62 additions & 0 deletions src/drivers/drv_dma_bitbang.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
/****************************************************************************
*
* 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_dma_bb.c
*
* DMA based Bit Bang Support
* Author: Siddharth Bharat Purohit
*
*/

#pragma once
#include <px4_config.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>

#include <sys/types.h>
#include <stdbool.h>
#include <inttypes.h>

#include <px4_time.h>
#include <queue.h>

__BEGIN_DECLS

/* Initialise DMA based Bitbanging scheme*/
__EXPORT extern void dma_bb_init(uint32_t mult, uint32_t offset);

/* Send buffer containing pin states to be sent immediately */
__EXPORT extern void dma_bb_send_buff(uint32_t* dat, uint32_t len, dma_callback_t callback, void* arg);

__END_DECLS
1 change: 1 addition & 0 deletions src/drivers/stm32/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ px4_add_module(
drv_io_timer.c
drv_pwm_servo.c
drv_input_capture.c
drv_dma_bitbang.c
DEPENDS
platforms__common
)
Expand Down
203 changes: 203 additions & 0 deletions src/drivers/stm32/drv_dma_bitbang.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,203 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file px4fmu_dma_bb.c
*
* DMA based Bit Bang driver
* Author: Siddharth Bharat Purohit
*
*/

/************************************************************************************
* Included Files
************************************************************************************/

#include <stdbool.h>
#include <stdio.h>
#include <assert.h>
#include <debug.h>
#include <time.h>
#include <queue.h>
#include <errno.h>
#include <string.h>
#include <math.h>

#include <drivers/drv_dma_bitbang.h>

#include "chip.h"
#include "up_internal.h"
#include "up_arch.h"

#include "stm32.h"
#include "stm32_gpio.h"
#include "stm32_tim.h"

#ifdef DMAMAP_BITBANG

#if TIMER_BITBANG == 1
# define DMA_TIMER_BASE STM32_TIM1_BASE
# define DMA_TIMER_POWER_REG STM32_RCC_APB2ENR
# define DMA_TIMER_POWER_BIT RCC_APB2ENR_TIM1EN
# define DMA_TIMER_VECTOR STM32_IRQ_TIM1CC
# define DMA_TIMER_CLOCK STM32_APB2_TIM1_CLKIN
#elif TIMER_BITBANG == 8
# define DMA_TIMER_BASE STM32_TIM8_BASE
# define DMA_TIMER_POWER_REG STM32_RCC_APB2ENR
# define DMA_TIMER_POWER_BIT RCC_APB2ENR_TIM8EN
# define DMA_TIMER_VECTOR STM32_IRQ_TIM8CC
# define DMA_TIMER_CLOCK STM32_APB2_TIM8_CLKIN

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

shouldn't all these defines be in board_config.h and then here you just error out if there's no define for BITBANG_DMA_TIMER_BASE?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am following the routine of other drivers under this category. If you look at driver for hrt and pwmin. they have same methodology for setting timer.

#else
# error must select Timer 1 or Timer 8 DMA2 doesnot support any other
#endif

/*
* Timer register accessors
*/
#define REG(_reg) (*(volatile uint32_t *)(DMA_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)


#if TIMER_BITBANG_CH == 1
# define rCCR_DMA rCCR1 /* compare register */
# define DIER_DMA_INT GTIM_DIER_CC1IE /* interrupt enable */
# define DIER_DMA_REQ GTIM_DIER_CC1DE /* DMA request enable */
# define SR_INT_DMA GTIM_SR_CC1IF /* interrupt status */
#elif TIMER_BITBANG_CH == 2
# define rCCR_DMA rCCR2 /* compare register */
# define DIER_DMA_INT GTIM_DIER_CC2IE /* interrupt enable */
# define DIER_DMA_REQ GTIM_DIER_CC2DE /* DMA request enable */
# define SR_INT_DMA GTIM_SR_CC2IF /* interrupt status */
#elif TIMER_BITBANG_CH == 3
# define rCCR_DMA rCCR3 /* compare register */
# define DIER_DMA_INT GTIM_DIER_CC3IE /* interrupt enable */
# define DIER_DMA_REQ GTIM_DIER_CC3DE /* DMA request enable */
# define SR_INT_DMA GTIM_SR_CC3IF /* interrupt status */
#elif TIMER_BITBANG_CH == 4
# define rCCR_DMA rCCR4 /* compare register */
# define DIER_DMA_INT GTIM_DIER_CC4IE /* interrupt enable */
# define DIER_DMA_REQ GTIM_DIER_CC4DE /* DMA request enable */
# define SR_INT_DMA GTIM_SR_CC4IF /* interrupt status */
#else
# error TIMER_BITBANG_CH must be a value between 1 and 4
#endif

static DMA_HANDLE tx_dma;

static void dma_reset(void);
static volatile bool dma_bitbang_initialized = false;

/* GPIO register accessors */
#define GPIO_REG(_x) (*(volatile uint32_t *)(BITBANG_GPIO_REG_BASE + _x))
#define rBSSR GPIO_REG(STM32_GPIO_BSRR_OFFSET)

// The rate of timer will be set per following equation
// Timer_Rate = {(16.8*mult + offset)/168} Mhz
// The fastest clock which can be generated would be:
// Clk_fast = Timer_Rate/4 Hz
void dma_bb_init(uint32_t mult, uint32_t offset)
{
/* clock/power on our timer */
modifyreg32(DMA_TIMER_POWER_REG, 0, DMA_TIMER_POWER_BIT);

tx_dma = stm32_dmachannel(DMAMAP_BITBANG);

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you need a call to configgpio to make sure the pin is configured to gpio.

Copy link
Member Author

@bugobliterator bugobliterator Aug 19, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am leaving off the load to declare the direction settings to HAL in APM via relevant functions. In APM this is going to be interfaced via GPIO methods.

/* configure the timer according to the requested factors*/
rPSC = roundf(16.8f * mult + offset) - 1;

/* run to only one increment*/
rARR = 1;

rCCR_DMA = 1;

rCR1 = 0;
rCR2 = 0;

/* generate an update event; reloads the counter, all registers */
rEGR = GTIM_EGR_UG;

/* enable the timer */
rCR1 = GTIM_CR1_CEN;

dma_bitbang_initialized = true;
printf("[init] Starting DMA bitbang driver \n");
}

/*
Sends Set or Reset data to GPIO Register popping data from top at every timer compare

-- "callback" is called after completion the set of requested pulse is transmitted through
to GPIO bus,
-- with "arg" being the argument to the callback
-- "dat" contains the list of pin states over time, data is sent to GPIOx_BSSR register which
has following behaviour:

-- Bits 31:16 BRx
0: No action
1: Reset the corresponding GPIOx O/P bit

-- Bits 15:0 BSx
0: No action
1: Set the corresponding GPIOx O/P bit

Note: If both BSx and BRx are set, BSx has priority.
*/
void dma_bb_send_buff(uint32_t* dat, uint32_t len, dma_callback_t callback, void* arg)
{
if (!dma_bitbang_initialized) {
return;
}
/* unconfigure the timer request */
rDIER &= ~DIER_DMA_REQ;
dma_reset();

stm32_dmasetup(
tx_dma,
(uint32_t)&rBSSR,
(uint32_t)dat,
len,
DMA_SCR_DIR_M2P |
DMA_SCR_MINC |
DMA_SCR_PSIZE_32BITS |
DMA_SCR_MSIZE_32BITS);
stm32_dmastart(tx_dma, callback, arg, false);

/* Enable Timer request */
rDIER |= DIER_DMA_REQ;
}

static void
dma_reset(void)
{
/* kill any pending DMA */
stm32_dmastop(tx_dma);
}

#endif //#ifdef DMAMAP_BITBANG
3 changes: 2 additions & 1 deletion src/drivers/stm32/module.mk
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@
SRCS = drv_hrt.c \
drv_pwm_servo.c \
drv_io_timer.c \
drv_input_capture.c
drv_input_capture.c \
drv_dma_bitbang.c


INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
Expand Down