cuav_can-gps-v1 Use SK6812 Serial PWM LED Driver

This commit is contained in:
David Sidrane 2021-01-19 05:59:35 -08:00 committed by Daniel Agar
parent 2c4d1d8fe0
commit 7800f94dcb
8 changed files with 79 additions and 67 deletions

View File

@ -17,6 +17,7 @@ add_definitions(
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major} -DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor} -DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
) )
add_definitions(-DUSE_S_RGB_LED_DMA)
px4_add_board( px4_add_board(
PLATFORM nuttx PLATFORM nuttx
@ -31,6 +32,7 @@ px4_add_board(
barometer/ms5611 barometer/ms5611
bootloaders bootloaders
gps gps
lights/neopixel
magnetometer/rm3100 magnetometer/rm3100
safety_button safety_button
tone_alarm tone_alarm

View File

@ -2,7 +2,7 @@
# #
# board specific defaults # board specific defaults
#------------------------------------------------------------------------------ #------------------------------------------------------------------------------
neopixel start
if [ $AUTOCNF = yes ] if [ $AUTOCNF = yes ]
then then

View File

@ -33,6 +33,7 @@
* POSSIBILITY OF SUCH DAMAGE. * POSSIBILITY OF SUCH DAMAGE.
* *
************************************************************************************/ ************************************************************************************/
#include "board_dma_map.h"
#ifndef __ARCH_BOARD_BOARD_H #ifndef __ARCH_BOARD_BOARD_H
#define __ARCH_BOARD_BOARD_H #define __ARCH_BOARD_BOARD_H

View File

@ -0,0 +1,44 @@
/****************************************************************************
*
* Copyright (c) 2021 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.
*
****************************************************************************/
#pragma once
// N.B. Map not included as it is not correct for an F412
// DMA1 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
// DMA2 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
#define DMAMAP_TIM1_CH2 DMAMAP_TIM1_CH2_2 // DMA2, Stream 6, Channel 6 SLED

View File

@ -36,14 +36,16 @@ if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
add_library(drivers_board add_library(drivers_board
boot_config.h boot_config.h
boot.c boot.c
led.c led.cpp
led.h led.h
) )
target_link_libraries(drivers_board target_link_libraries(drivers_board
PRIVATE PRIVATE
nuttx_arch nuttx_arch
nuttx_drivers nuttx_drivers
canbootloader canbootloader
platform_srgbled
) )
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader) target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader)

View File

@ -51,6 +51,9 @@
#define BUTTON_SAFETY /* PB3 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN3|GPIO_EXTI) #define BUTTON_SAFETY /* PB3 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN3|GPIO_EXTI)
#define GPIO_RGB_S /* PB0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0) #define GPIO_RGB_S /* PB0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
#define BOARD_SRGBLED_PORT STM32_GPIOB_ODR
#define BOARD_SRGBLED_BIT 0
/* CAN Silence /* CAN Silence
* *
* Silent mode control \ ESC Mux select * Silent mode control \ ESC Mux select
@ -71,7 +74,22 @@
#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */ #define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */
__BEGIN_DECLS __BEGIN_DECLS
#define BOARD_HAS_N_S_RGB_LED 8 /* Uses 8 SK6812 digital led chip */
#define BOARD_MAX_LEDS BOARD_HAS_N_S_RGB_LED
/* USE_S_RGB_LED_DMAis passed in from the *.cmake file
* Bootloader is not timming sensitive and can use the SW version as a
* size savings
* The Application can not as it needs DMA to maintain reall time.
*/
#if defined(USE_S_RGB_LED_DMA)
# define S_RGB_LED_DMA DMAMAP_TIM1_CH2
# define S_RGB_LED_TIMER 1 /* timer 1 */
# define S_RGB_LED_CHANNEL 2 /* channel 2 */
# define S_RGB_LED_CHANNELN 1 /* channel 2N */
# define S_RGB_LED_TIM_GPIO GPIO_TIM1_CH2N_1
#endif
#ifndef __ASSEMBLY__ #ifndef __ASSEMBLY__
/**************************************************************************************************** /****************************************************************************************************

View File

@ -70,7 +70,7 @@
#define OPT_NODE_STATUS_RATE_MS 800 #define OPT_NODE_STATUS_RATE_MS 800
#define OPT_NODE_INFO_RATE_MS 50 #define OPT_NODE_INFO_RATE_MS 50
#define OPT_BL_NUMBER_TIMERS 7 #define OPT_BL_NUMBER_TIMERS 7
#undef S_RGB_LED_DMA // use the poled one
/* /*
* This Option set is set to 1 ensure a provider of firmware has an * This Option set is set to 1 ensure a provider of firmware has an
* opportunity update the node's firmware. * opportunity update the node's firmware.

View File

@ -41,6 +41,7 @@
#include <hardware/stm32_tim.h> #include <hardware/stm32_tim.h>
#include <dwt.h> #include <dwt.h>
#include <nvic.h> #include <nvic.h>
#include <drivers/drv_neopixel.h>
#include "led.h" #include "led.h"
@ -48,67 +49,15 @@
#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN #define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN
#define TMR_REG(o) (TMR_BASE+(o)) #define TMR_REG(o) (TMR_BASE+(o))
#define LED_COUNT 8 // Eight LEDs in ring static uint8_t _rgb[] = {0, 0, 0};
typedef union {
uint8_t grb[3];
uint32_t l;
} led_data_t;
static uint8_t off[] = {0, 0, 0};
#define REG(_addr) (*(volatile uint32_t *)(_addr))
#define rDEMCR REG(NVIC_DEMCR)
#define rDWT_CTRL REG(DWT_CTRL)
#define rDWT_CNT REG(DWT_CYCCNT)
#define PORT_B REG(STM32_GPIOB_ODR)
#define D0 REG(STM32_GPIOB_ODR) &= ~1;
#define D1 REG(STM32_GPIOB_ODR) |= 1;
#define DWT_DEADLINE(t) rDWT_CNT + (t)
#define DWT_WAIT(v, D) while((rDWT_CNT - (v)) < (D));
#define T0H (STM32_SYSCLK_FREQUENCY/3333333)
#define T1H (STM32_SYSCLK_FREQUENCY/1666666)
#define TW (STM32_SYSCLK_FREQUENCY/800000)
static void setled(uint8_t *p, int count)
{
rDEMCR |= NVIC_DEMCR_TRCENA;
rDWT_CTRL |= DWT_CTRL_CYCCNTENA_MASK;
while (count--) {
uint8_t l = *p++;
uint32_t deadline = DWT_DEADLINE(TW);
for (uint32_t mask = (1 << 7); mask != 0; mask >>= 1) {
DWT_WAIT(deadline, TW);
deadline = rDWT_CNT;
D1;
if (l & mask) {
DWT_WAIT(deadline, T1H);
} else {
DWT_WAIT(deadline, T0H);
}
D0;
}
DWT_WAIT(deadline, TW);
}
}
static led_data_t led_data = {0};
static int timerInterrupt(int irq, void *context, void *arg) static int timerInterrupt(int irq, void *context, void *arg)
{ {
putreg16(~getreg16(TMR_REG(STM32_GTIM_SR_OFFSET)), TMR_REG(STM32_GTIM_SR_OFFSET)); putreg16(~getreg16(TMR_REG(STM32_GTIM_SR_OFFSET)), TMR_REG(STM32_GTIM_SR_OFFSET));
static int d2 = 1; static int d2 = 1;
setled((d2++ & 1) ? led_data.grb : off, sizeof(led_data.grb)); (d2++ & 1) ? neopixel_write_no_dma(0, 0, 0, 1) : neopixel_write_no_dma(_rgb[0], _rgb[1], _rgb[2], 1);
return 0; return 0;
} }
@ -126,11 +75,7 @@ void rgb_led(int r, int g, int b, int freqs)
stm32_configgpio(GPIO_RGB_S); stm32_configgpio(GPIO_RGB_S);
for (int i = 0; i < LED_COUNT; i++) { neopixel_write_no_dma(0, 0, 0, BOARD_HAS_N_S_RGB_LED);
setled(off, sizeof(off));
}
/* Enable Clock to Block */
modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN); modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN);
@ -156,10 +101,10 @@ void rgb_led(int r, int g, int b, int freqs)
long p = freqs == 0 ? p1s + 1 : p0p5s / freqs; long p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
putreg32(p + 1, TMR_REG(STM32_BTIM_ARR_OFFSET)); putreg32(p + 1, TMR_REG(STM32_BTIM_ARR_OFFSET));
putreg32(p, TMR_REG(STM32_GTIM_CCR1_OFFSET)); putreg32(p, TMR_REG(STM32_GTIM_CCR1_OFFSET));
led_data.grb[0] = g; _rgb[0] = r;
led_data.grb[1] = r; _rgb[1] = g;
led_data.grb[2] = b; _rgb[2] = b;
setled(led_data.grb, sizeof(led_data.grb)); neopixel_write_no_dma(_rgb[0], _rgb[1], _rgb[2], 1);
val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET)); val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));