New implementation of the ESP32's RMT driver.

This commit is contained in:
Victor Benso 2023-07-01 12:18:07 -03:00 committed by Alan Carvalho de Assis
parent f3e22c0bb0
commit 0c5145b7d1
15 changed files with 1587 additions and 6 deletions

38
Kconfig
View File

@ -1619,6 +1619,44 @@ config DEBUG_RC_INFO
endif # DEBUG_RC
config DEBUG_RMT
bool "RMT Debug Features"
default n
depends on ESP32_RMT
---help---
Enable RMT debug features.
Support for this debug option is architecture-specific and may not
be available for some MCUs.
if DEBUG_RMT
config DEBUG_RMT_ERROR
bool "RMT Error Output"
default n
depends on DEBUG_ERROR
---help---
Enable RMT driver error output to SYSLOG.
Support for this debug option is architecture-specific and may not
be available for some MCUs.
config DEBUG_RMT_WARN
bool "RMT Warnings Output"
default n
depends on DEBUG_WARN
---help---
Enable RMT driver warning output to SYSLOG.
config DEBUG_RMT_INFO
bool "RMT Informational Output"
default n
depends on DEBUG_INFO
---help---
Enable RMT driver informational output to SYSLOG.
endif # DEBUG_RMT
config DEBUG_RTC
bool "RTC Debug Features"
default n

View File

@ -82,6 +82,10 @@ ifeq ($(CONFIG_ESP32_PCNT_AS_QE),y)
CHIP_CSRCS += esp32_qencoder.c
endif
ifeq ($(CONFIG_ESP32_RMT),y)
CHIP_CSRCS += esp32_rmt.c
endif
ifeq ($(CONFIG_ESP32_SPI),y)
CHIP_CSRCS += esp32_spi.c
ifeq ($(CONFIG_SPI_SLAVE),y)

View File

@ -0,0 +1,436 @@
/****************************************************************************
* arch/xtensa/src/esp32/esp32_rmt.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <sys/types.h>
#include <inttypes.h>
#include <stdint.h>
#include <stdbool.h>
#include <assert.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/kmalloc.h>
#include <arch/board/board.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/spinlock.h>
#include "xtensa.h"
#include "esp32_gpio.h"
#include "esp32_rmt.h"
#include "esp32_irq.h"
#include "esp32_clockconfig.h"
#include "hardware/esp32_dport.h"
#include "hardware/esp32_gpio_sigmap.h"
#ifdef CONFIG_ESP32_RMT
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/* RMT methods */
static void rmt_reset(struct rmt_dev_s *dev);
static int rmt_setup(struct rmt_dev_s *dev);
IRAM_ATTR static int rmt_interrupt(int irq, void *context, void *arg);
/****************************************************************************
* Private Data
****************************************************************************/
struct rmt_dev_s g_rmt_dev =
{
.periph = ESP32_PERIPH_RMT,
.irq = ESP32_IRQ_RMT,
.cpu = 0,
.cpuint = -ENOMEM,
.lock = 0
};
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: rmt_reset
*
* Description:
* Reset the RMT device. Called early to initialize the hardware. This
* function is called, before esp32_rmt_setup().
*
* Input Parameters:
* dev - An instance of the "upper half" RMT driver state structure.
*
* Returned Value:
* None
*
****************************************************************************/
static void rmt_reset(struct rmt_dev_s *dev)
{
irqstate_t flags;
flags = spin_lock_irqsave(&dev->lock);
modifyreg32(DPORT_PERIP_RST_EN_REG, DPORT_RMT_RST, 1);
modifyreg32(DPORT_PERIP_RST_EN_REG, DPORT_RMT_RST, 0);
/* Clear any spurious IRQ Flag */
putreg32(0xffffffff, RMT_INT_CLR_REG);
/* Enable memory wrap-around */
modifyreg32(RMT_APB_CONF_REG, 0 , BIT(1));
spin_unlock_irqrestore(&dev->lock, flags);
}
/****************************************************************************
* Name: rmt_setup
*
* Description:
* Configure the RMT. This method is called the first time that the RMT
* device is opened. This will occur when the port is first opened.
* This setup includes configuring and attaching RMT interrupts.
*
* Input Parameters:
* dev - An instance of the "upper half" RMT driver state structure.
*
* Returned Value:
* Zero on success; a negated errno on failure
*
****************************************************************************/
static int rmt_setup(struct rmt_dev_s *dev)
{
irqstate_t flags;
int ret = OK;
flags = spin_lock_irqsave(&dev->lock);
if (dev->cpuint != -ENOMEM)
{
/* Disable the provided CPU Interrupt to configure it. */
up_disable_irq(dev->cpuint);
}
dev->cpu = up_cpu_index();
dev->cpuint = esp32_setup_irq(dev->cpu, dev->periph,
1, ESP32_CPUINT_LEVEL);
if (dev->cpuint < 0)
{
/* Failed to allocate a CPU interrupt of this type. */
ret = dev->cpuint;
spin_unlock_irqrestore(&dev->lock, flags);
return ret;
}
ret = irq_attach(dev->irq, rmt_interrupt, dev);
if (ret != OK)
{
/* Failed to attach IRQ, so CPU interrupt must be freed. */
esp32_teardown_irq(dev->cpu, dev->periph, dev->cpuint);
dev->cpuint = -ENOMEM;
spin_unlock_irqrestore(&dev->lock, flags);
return ret;
}
/* Enable the CPU interrupt that is linked to the RMT device. */
up_enable_irq(dev->irq);
spin_unlock_irqrestore(&dev->lock, flags);
return ret;
}
/****************************************************************************
* Name: rmt_load_tx_buffer
*
* Description:
* Copies chunks of data from the buffer to the RMT device memory
* This function can also be called on the first transmition data chunk
*
* Input Parameters:
* channel - Pointer to the channel to be reloaded
*
* Returned Value:
* None
*
****************************************************************************/
IRAM_ATTR void rmt_load_tx_buffer(struct rmt_dev_channel_s *channel)
{
uint32_t *src = channel->src;
uint32_t dst_mem;
uint32_t buffer_size;
if (channel->src_offset == 0)
{
buffer_size = channel->available_words;
dst_mem = channel->start_address;
channel->next_buffer = 0;
}
else
{
buffer_size = channel->reload_thresh;
dst_mem = channel->start_address +
4*channel->next_buffer*channel->reload_thresh;
/* only swap buffers after the first call */
if (channel->next_buffer == 0)
{
channel->next_buffer = 1;
}
else
{
channel->next_buffer = 0;
}
}
while (channel->src_offset < channel->words_to_send && buffer_size > 0)
{
uint32_t word_to_send = *(src + channel->src_offset);
putreg32(word_to_send, dst_mem);
channel->src_offset++;
dst_mem += 4;
buffer_size--;
}
/* Adding 0x00 on RMT's buffer marks the EOT */
if (channel->src_offset == channel->words_to_send && buffer_size > 0)
{
putreg32(0x00, dst_mem);
}
}
/****************************************************************************
* Name: rmt_interrupt
*
* Description:
* RMT TX interrupt handler
*
* Input Parameters:
* irq - The IRQ number of the interrupt.
* context - The register state save array at the time of the interrupt.
* arg - The pointer to driver structure.
*
* Returned Value:
* Zero on success; a negated errno on failure
*
****************************************************************************/
IRAM_ATTR static int rmt_interrupt(int irq, void *context, void *arg)
{
struct rmt_dev_s *dev = (struct rmt_dev_s *)arg;
uint32_t regval = getreg32(RMT_INT_ST_REG);
uint8_t error_flag = 0;
int flags = spin_lock_irqsave(&dev->lock);
for (int ch_idx = 0; ch_idx < RMT_NUMBER_OF_CHANNELS; ch_idx++)
{
struct rmt_dev_channel_s *channel_data =
(struct rmt_dev_channel_s *) &(dev->channels[ch_idx]);
/* IRQs from channels with no pins, should be ignored */
if (channel_data->output_pin < 0)
{
putreg32(RMT_CHN_TX_THR_EVENT_INT_CLR(ch_idx), RMT_INT_CLR_REG);
putreg32(RMT_CHN_TX_END_INT_CLR(ch_idx), RMT_INT_CLR_REG);
continue;
}
if (regval & RMT_CHN_TX_THR_EVENT_INT_ST(ch_idx))
{
putreg32(RMT_CHN_TX_THR_EVENT_INT_CLR(ch_idx), RMT_INT_CLR_REG);
/* buffer refill */
rmt_load_tx_buffer(channel_data);
}
else if (regval & RMT_CHN_TX_END_INT_ST(ch_idx))
{
/* end of transmition */
modifyreg32(RMT_INT_ENA_REG,
RMT_CHN_TX_END_INT_ENA(ch_idx) |
RMT_CHN_TX_THR_EVENT_INT_ENA(ch_idx),
0
);
putreg32(RMT_CHN_TX_END_INT_CLR(ch_idx), RMT_INT_CLR_REG);
putreg32(RMT_CHN_TX_THR_EVENT_INT_CLR(ch_idx), RMT_INT_CLR_REG);
/* release the lock so the write function can return */
nxsem_post(&channel_data->tx_sem);
}
}
if (error_flag)
{
/* clear any spurious IRQ flag */
putreg32(0xffffffff, RMT_INT_CLR_REG);
}
spin_unlock_irqrestore(&dev->lock, flags);
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: esp32_rmtinitialize
*
* Description:
* Initialize the selected RMT device
*
* Input Parameters:
*
* Returned Value:
* Valid RMT device structure reference on success; a NULL on failure
*
****************************************************************************/
struct rmt_dev_s *esp32_rmtinitialize(void)
{
struct rmt_dev_s *rmtdev = &g_rmt_dev;
irqstate_t flags;
flags = spin_lock_irqsave(&rmtdev->lock);
modifyreg32(DPORT_PERIP_CLK_EN_REG, 0, DPORT_RMT_CLK_EN);
modifyreg32(DPORT_PERIP_RST_EN_REG, DPORT_RMT_RST, 0);
spin_unlock_irqrestore(&rmtdev->lock, flags);
rmt_reset(rmtdev);
rmt_setup(rmtdev);
rmtdev->channels = kmm_zalloc(
sizeof(struct rmt_dev_channel_s)*
RMT_NUMBER_OF_CHANNELS
);
if (!rmtdev->channels)
{
rmterr("Failed to allocate memory for RMT Channels");
return NULL;
}
for (int ch_idx = 0; ch_idx < RMT_NUMBER_OF_CHANNELS; ch_idx++)
{
struct rmt_dev_channel_s *channel_data =
(struct rmt_dev_channel_s *) &(rmtdev->channels[ch_idx]);
channel_data->open_count = 0;
channel_data->ch_idx = ch_idx;
channel_data->output_pin = -1;
channel_data->available_words = 64;
uint32_t start_addr_chn = RMT_DATA_BASE_ADDR +
RMT_DATA_MEMORY_BLOCK_WORDS * 4 * ch_idx;
channel_data->start_address = start_addr_chn;
channel_data->reload_thresh = channel_data->available_words / 2;
channel_data->parent_dev = rmtdev;
}
return rmtdev;
}
/****************************************************************************
* Name: rmt_attach_pin_to_channel
*
* Description:
* Binds a gpio pin to a RMT channel
*
* Input Parameters:
* rmtdev - pointer the rmt device, needed for the locks
* output_pin - the pin used for output
* channel - the RMT's channel that will be used
*
* Returned Value:
* Zero on success; a negated errno on failure
*
****************************************************************************/
int rmt_attach_pin_to_channel(struct rmt_dev_s *rmtdev, int ch_idx, int pin)
{
irqstate_t flags;
if (ch_idx >= RMT_NUMBER_OF_CHANNELS || pin < 0)
{
return -EINVAL;
}
flags = spin_lock_irqsave(&rmtdev->lock);
struct rmt_dev_channel_s *channel_data =
(struct rmt_dev_channel_s *) &(rmtdev->channels[ch_idx]);
channel_data->output_pin = pin;
nxsem_init(&channel_data->tx_sem, 0, 1);
/* Configure RMT GPIO pin */
esp32_gpio_matrix_out(pin, RMT_SIG_OUT0_IDX + ch_idx, 0, 0);
esp32_configgpio(pin, OUTPUT_FUNCTION_1);
spin_unlock_irqrestore(&rmtdev->lock, flags);
return OK;
}
#endif

View File

@ -0,0 +1,164 @@
/****************************************************************************
* arch/xtensa/src/esp32/esp32_rmt.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __ARCH_XTENSA_SRC_ESP32_ESP32_RMT_H
#define __ARCH_XTENSA_SRC_ESP32_ESP32_RMT_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <semaphore.h>
#include <nuttx/spinlock.h>
#include "hardware/esp32_rmt.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
struct rmt_dev_channel_s
{
/* Parameters for each RMT channel */
int open_count;
int ch_idx;
int output_pin;
int next_buffer;
sem_t tx_sem;
uint32_t *src;
uint32_t src_offset;
size_t words_to_send;
uint32_t available_words;
uint32_t start_address;
uint32_t reload_thresh;
void *parent_dev;
};
struct rmt_dev_s
{
/* Device configuration */
uint8_t periph; /* Peripheral ID */
uint8_t irq; /* IRQ associated with this RMT */
uint8_t cpu; /* CPU ID */
int cpuint; /* CPU interrupt assigned to this RMT */
spinlock_t lock;
struct rmt_dev_channel_s *channels;
};
/****************************************************************************
* Public Data
****************************************************************************/
#ifndef __ASSEMBLY__
#ifdef __cplusplus
extern "C"
{
#endif
/****************************************************************************
* Public Functions Prototypes
****************************************************************************/
#if defined(CONFIG_ESP32_RMT)
/****************************************************************************
* Name: rmt_load_tx_buffer
*
* Description:
* Copies chunks of data from the buffer to the RMT device memory
* This function can also be called on the first transmition data chunk
*
* Input Parameters:
* channel - Pointer to the channel to be reloaded
*
* Returned Value:
* None
*
****************************************************************************/
IRAM_ATTR void rmt_load_tx_buffer(struct rmt_dev_channel_s *channel);
/****************************************************************************
* Name: esp32_rmtinitialize
*
* Description:
* Initialize the selected RMT device
*
* Input Parameters:
*
* Returned Value:
* Valid RMT device structure reference on success; a NULL on failure
*
****************************************************************************/
struct rmt_dev_s *esp32_rmtinitialize(void);
/****************************************************************************
* Name: rmt_attach_pin_to_channel
*
* Description:
* Binds a gpio pin to a RMT channel
*
* Input Parameters:
* rmtdev - pointer the rmt device, needed for the locks
* output_pin - the pin used for output
* channel - the RMT's channel that will be used
*
* Returned Value:
* Zero on success; a negated errno on failure
*
****************************************************************************/
int rmt_attach_pin_to_channel(struct rmt_dev_s *rmtdev, int ch_idx, int pin);
/****************************************************************************
* Name: board_rmt_initialize
*
* Description:
* Initialize RMT driver and register the channel/pin pair at /dev/rtm0
*
* Input Parameters:
* output_pin - the output pin to assing to the channel
* channel - the channel that will be initialized
*
* Returned Value:
* Zero (OK) is returned on success; A negated errno value is returned
* to indicate the nature of any failure.
*
****************************************************************************/
int board_rmt_initialize(int output_pin, int channel);
#endif
#ifdef __cplusplus
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_XTENSA_SRC_ESP32_ESP32_RMT_H */

View File

@ -0,0 +1,266 @@
/****************************************************************************
* arch/xtensa/src/esp32/hardware/esp32_rmt.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_RMT_H
#define __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_RMT_H
/****************************************************************************
* Included Files
****************************************************************************/
#include "esp32_soc.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* RMT Peripheral constants */
#define RMT_NUMBER_OF_CHANNELS 8
#define RMT_DATA_BASE_ADDR 0x3ff56800
#define RMT_DATA_MEMORY_BLOCK_WORDS 64
/* RMT Channel configuration registers */
#define RMT_CHNCONF_REG_BASE (DR_REG_RMT_BASE+0x20)
#define RMT_CHNCONF0_REG(n) (RMT_CHNCONF_REG_BASE + 8*n)
#define RMT_CHNCONF1_REG(n) (RMT_CHNCONF0_REG(n) + 4)
#define RMT_INT_RAW_REG (DR_REG_RMT_BASE+0x00A0)
#define RMT_INT_ST_REG (DR_REG_RMT_BASE+0x00A4)
#define RMT_INT_ENA_REG (DR_REG_RMT_BASE+0x00A8)
#define RMT_INT_CLR_REG (DR_REG_RMT_BASE+0x00AC)
#define RMT_CHNCARRIER_DUTY_REG(n) (DR_REG_RMT_BASE + 0x00B0+4*n)
#define RMT_CHN_TX_LIM_REG(n) (DR_REG_RMT_BASE + 0x00D0+4*n)
#define RMT_APB_CONF_REG (DR_REG_RMT_BASE + 0x00F0)
/* RMT_CHNCONF0_REG Bits */
/* RMT_MEM_PD: This bit is used to power down the entire RMT RAM block.
* (It only exists in RMT_CH0CONF0).
* 1: power down memory; 0: power up memory. (R/W)
*/
#define RMT_MEM_PD BIT(30)
#define RMT_MEM_PD_M (RMT_MEM_PD_V << RMT_MEM_PD_S)
#define RMT_MEM_PD_V 0x00000001
#define RMT_MEM_PD_S 30
/* RMT_CARRIER_OUT_LV_CHN This bit is used for configuration when the
* carrier wave is being transmitted. Transmit on low output level with 0,
* and transmit on high output level with 1. (R/W)
*/
#define RMT_CARRIER_OUT_LV_CHN BIT(29)
#define RMT_CARRIER_OUT_LV_CHN_M (RMT_CARRIER_OUT_LV_CHN_V << RMT_CARRIER_OUT_LV_CHN_S)
#define RMT_CARRIER_OUT_LV_CHN_V 0x00000001
#define RMT_CARRIER_OUT_LV_CHN_S 29
/* RMT_CARRIER_EN_CHN This is the carrier modulation enable-control bit
* for channel n. Carrier modulation is enabled with 1, while carrier
* modulation is disabled with 0. (R/W)
*/
#define RMT_CARRIER_EN_CHN BIT(28)
#define RMT_CARRIER_EN_CHN_M (RMT_CARRIER_EN_CHN_V << RMT_CARRIER_EN_CHN_S)
#define RMT_CARRIER_EN_CHN_V 0x00000001
#define RMT_CARRIER_EN_CHN_S 28
/* RMT_MEM_SIZE_CHN This register is used to configure the amount of
* memory blocks allocated to channel n. (R/W)
*/
#define RMT_MEM_SIZE_CHN BIT(24)
#define RMT_MEM_SIZE_CHN_M (RMT_MEM_SIZE_CHN_V << RMT_MEM_SIZE_CHN_S)
#define RMT_MEM_SIZE_CHN_V 0x00000001
#define RMT_MEM_SIZE_CHN_S 24
/* RMT_IDLE_THRES_CHN In receive mode, when no edge is detected on
* the input signal for longer than REG_IDLE_THRES_CHN channel clock cycles,
* the receive process is finished. (R/W)
*/
#define RMT_IDLE_THRES_CHN BIT(8)
#define RMT_IDLE_THRES_CHN_M (RMT_IDLE_THRES_CHN_V << RMT_IDLE_THRES_CHN_S)
#define RMT_IDLE_THRES_CHN_V 0x00000001
#define RMT_IDLE_THRES_CHN_S 8
/* RMT_DIV_CNT_CHN This register is used to set the divider for the channel
* clock of channel n. (R/W)
*/
#define RMT_DIV_CNT_CHN BIT(0)
#define RMT_DIV_CNT_CHN_M (RMT_DIV_CNT_CHN_V << RMT_DIV_CNT_CHN_S)
#define RMT_DIV_CNT_CHN_V 0x00000001
#define RMT_DIV_CNT_CHN_S 0
/* RMT_CHNCONF1_REG Bits */
/* RMT_IDLE_OUT_EN_CHN This is the output enable-control bit for channel n
* in IDLE state. (R/W)
*/
#define RMT_IDLE_OUT_EN_CHN BIT(19)
#define RMT_IDLE_OUT_EN_CHN_M (RMT_IDLE_OUT_EN_CHN_V << RMT_IDLE_OUT_EN_CHN_S)
#define RMT_IDLE_OUT_EN_CHN_V 0x00000001
#define RMT_IDLE_OUT_EN_CHN_S 19
/* RMT_IDLE_OUT_LV_CHN This bit configures the level of output signals
* in channel n when the latter is in IDLE state. (R/W)
*/
#define RMT_IDLE_OUT_LV_CHN BIT(18)
#define RMT_IDLE_OUT_LV_CHN_M (RMT_IDLE_OUT_LV_CHN_V << RMT_IDLE_OUT_LV_CHN_S)
#define RMT_IDLE_OUT_LV_CHN_V 0x00000001
#define RMT_IDLE_OUT_LV_CHN_S 18
/* RMT_REF_ALWAYS_ON_CHN This bit is used to select the channel's base
* clock. 1:clk_apb; 0:clk_ref. (R/W)
*/
#define RMT_REF_ALWAYS_ON_CHN BIT(17)
#define RMT_REF_ALWAYS_ON_CHN_M (RMT_REF_ALWAYS_ON_CHN_V << RMT_REF_ALWAYS_ON_CHN_S)
#define RMT_REF_ALWAYS_ON_CHN_V 0x00000001
#define RMT_REF_ALWAYS_ON_CHN_S 17
/* RMT_REF_CNT_RST_CHN Setting this bit resets the clock divider of channel
* n. (R/W)
*/
#define RMT_REF_CNT_RST_CHN BIT(16)
#define RMT_REF_CNT_RST_CHN_M (RMT_REF_CNT_RST_CHN_V << RMT_REF_CNT_RST_CHN_S)
#define RMT_REF_CNT_RST_CHN_V 0x00000001
#define RMT_REF_CNT_RST_CHN_S 16
/* RMT_RX_FILTER_THRES_CHN In receive mode, channel n ignores input
* pulse when the pulse width is smaller than this value in APB clock
* periods. (R/W)
*/
#define RMT_RX_FILTER_THRES_CHN BIT(8)
#define RMT_RX_FILTER_THRES_CHN_M (RMT_RX_FILTER_THRES_CHN_V << RMT_RX_FILTER_THRES_CHN_S)
#define RMT_RX_FILTER_THRES_CHN_V 0x00000001
#define RMT_RX_FILTER_THRES_CHN_S 8
/* RMT_RX_FILTER_EN_CHN This is the receive filter's enable-bit for channel
* n. (R/W)
*/
#define RMT_RX_FILTER_EN_CHN BIT(7)
#define RMT_RX_FILTER_EN_CHN_M (RMT_RX_FILTER_EN_CHN_V << RMT_RX_FILTER_EN_CHN_S)
#define RMT_RX_FILTER_EN_CHN_V 0x00000001
#define RMT_RX_FILTER_EN_CHN_S 7
/* RMT_TX_CONTI_MODE_CHN If this bit is set, instead of going to an idle
* state when transmission ends, the transmitter will restart transmission.
* This results in a repeating output signal. (R/W)
*/
#define RMT_TX_CONTI_MODE_CHN BIT(6)
#define RMT_TX_CONTI_MODE_CHN_M (RMT_TX_CONTI_MODE_CHN_V << RMT_TX_CONTI_MODE_CHN_S)
#define RMT_TX_CONTI_MODE_CHN_V 0x00000001
#define RMT_TX_CONTI_MODE_CHN_S 6
/* RMT_MEM_OWNER_CHN This bit marks channel n's RAM block ownership.
* Number 1 indicates that the receiver is using the RAM, while 0 indicates
* that the transmitter is using the RAM. (R/W)
*/
#define RMT_MEM_OWNER_CHN BIT(5)
#define RMT_MEM_OWNER_CHN_M (RMT_MEM_OWNER_CHN_V << RMT_MEM_OWNER_CHN_S)
#define RMT_MEM_OWNER_CHN_V 0x00000001
#define RMT_MEM_OWNER_CHN_S 5
/* RMT_MEM_RD_RST_CHN Set this bit to reset the read-RAM address for channel
* n by accessing the transmitter. (R/W)
*/
#define RMT_MEM_RD_RST_CHN BIT(3)
#define RMT_MEM_RD_RST_CHN_M (RMT_MEM_RD_RST_CHN_V << RMT_MEM_RD_RST_CHN_S)
#define RMT_MEM_RD_RST_CHN_V 0x00000001
#define RMT_MEM_RD_RST_CHN_S 3
/* RMT_MEM_WR_RST_CHN Set this bit to reset the write-RAM address for
* channel n by accessing the receiver. (R/W)
*/
#define RMT_MEM_WR_RST_CHN BIT(2)
#define RMT_MEM_WR_RST_CHN_M (RMT_MEM_WR_RST_CHN_V << RMT_MEM_WR_RST_CHN_S)
#define RMT_MEM_WR_RST_CHN_V 0x00000001
#define RMT_MEM_WR_RST_CHN_S 2
/* RMT_RX_EN_CHN Set this bit to enable receiving data on channel n. (R/W) */
#define RMT_RX_EN_CHN BIT(1)
#define RMT_RX_EN_CHN_M (RMT_RX_EN_CHN_V << RMT_RX_EN_CHN_S)
#define RMT_RX_EN_CHN_V 0x00000001
#define RMT_RX_EN_CHN_S 1
/* RMT_TX_START_CHN Set this bit to start sending data on channel n. (R/W) */
#define RMT_TX_START_CHN(n) BIT(n)
#define RMT_TX_START_CHN_M (RMT_TX_START_CHN_V << RMT_TX_START_CHN_S)
#define RMT_TX_START_CHN_V 0x00000001
#define RMT_TX_START_CHN_S 0
/* RMT_INT_RAW_REG Bits */
/* RMT_CHN_TX_THR_EVENT_INT_RAW The raw interrupt status bit for the
* RMT_CHN_TX_THR_EVENT_INT interrupt. (RO)
*/
#define RMT_CHN_TX_THR_EVENT_INT_RAW(n) BIT(24+n)
/* RMT_CHN_ERR_INT_RAW The raw interrupt status bit for the RMT_CHN_ERR_INT
* interrupt. (RO)
*/
#define RMT_CHN_ERR_INT_RAW(n) BIT(3*n+2)
/* RMT_CHN_RX_END_INT_RAW The raw interrupt status bit for
* the RMT_CHN_RX_END_INT interrupt. (RO)
*/
#define RMT_CHN_RX_END_INT_RAW(n) BIT(3*n+1)
/* RMT_CHN_TX_END_INT_RAW The raw interrupt status bit for the
* RMT_CHN_TX_END_INT interrupt. (RO)
*/
#define RMT_CHN_TX_END_INT_RAW(n) BIT(3*n)
/* RMT_INT_ST_REG Bits */
#define RMT_CHN_TX_THR_EVENT_INT_ST(n) BIT(24+n)
#define RMT_CHN_ERR_INT_ST(n) BIT(3*n+2)
#define RMT_CHN_RX_END_INT_ST(n) BIT(3*n+1)
#define RMT_CHN_TX_END_INT_ST(n) BIT(3*n)
/* RMT_INT_ENA_REG Bits */
#define RMT_CHN_TX_THR_EVENT_INT_ENA(n) BIT(24+n)
#define RMT_CHN_ERR_INT_ENA(n) BIT(3*n+2)
#define RMT_CHN_RX_END_INT_ENA(n) BIT(3*n+1)
#define RMT_CHN_TX_END_INT_ENA(n) BIT(3*n)
/* RMT_INT_CLR_REG Bits */
#define RMT_CHN_TX_THR_EVENT_INT_CLR(n) BIT(24+n)
#define RMT_CHN_ERR_INT_CLR(n) BIT(3*n+2)
#define RMT_CHN_RX_END_INT_CLR(n) BIT(3*n+1)
#define RMT_CHN_TX_END_INT_CLR(n) BIT(3*n)
#endif /* __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_RMT_H */

View File

@ -0,0 +1,67 @@
/****************************************************************************
* boards/xtensa/esp32/common/include/esp32_rmt.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __BOARDS_XTENSA_ESP32_COMMON_INCLUDE_ESP32_RMT_H
#define __BOARDS_XTENSA_ESP32_COMMON_INCLUDE_ESP32_RMT_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Type Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Inline Functions
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __BOARDS_XTENSA_ESP32_COMMON_INCLUDE_ESP32_RMT_H */

View File

@ -124,6 +124,10 @@ ifeq ($(CONFIG_RGBLED),y)
CSRCS += esp32_rgbled.c
endif
ifeq ($(CONFIG_ESP32_RMT),y)
CSRCS += esp32_rmt.c
endif
DEPPATH += --dep-path src
VPATH += :src
CFLAGS += ${INCDIR_PREFIX}$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)src

View File

@ -0,0 +1,282 @@
/****************************************************************************
* boards/xtensa/esp32/common/src/esp32_rmt.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <errno.h>
#include <debug.h>
#include <stdio.h>
#include "xtensa.h"
#include <nuttx/kmalloc.h>
#include "esp32_rmt.h"
#ifdef CONFIG_ESP32_RMT
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define APB_PERIOD (12.5)
#define T0H ((uint16_t)(350 / APB_PERIOD)) // ns
#define T0L ((uint16_t)(900 / APB_PERIOD)) // ns
#define T1H ((uint16_t)(900 / APB_PERIOD)) // ns
#define T1L ((uint16_t)(350 / APB_PERIOD)) // ns
#define RES ((uint16_t)(60000 / APB_PERIOD)) // ns
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
static int rmt_open(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct rmt_dev_channel_s *dev_data = inode->i_private;
FAR struct rmt_dev_s *parent_dev =
(struct rmt_dev_s *)dev_data->parent_dev;
int ret;
irqstate_t flags;
DEBUGASSERT(parent_dev);
nxsem_wait(&dev_data->tx_sem);
flags = spin_lock_irqsave(&parent_dev->lock);
if (dev_data->open_count == 0)
{
int ch_idx = dev_data->ch_idx;
uint32_t reg0_addr = RMT_CHNCONF0_REG(ch_idx);
uint32_t reg1_addr = RMT_CHNCONF1_REG(ch_idx);
uint32_t reg_val = 0x00;
/* a single memory block with double buffering is enough */
uint32_t mem_blocks = 1;
dev_data->available_words = RMT_DATA_MEMORY_BLOCK_WORDS*mem_blocks;
dev_data->reload_thresh = dev_data->available_words / 2;
uint32_t start_addr_chn = RMT_DATA_BASE_ADDR +
RMT_DATA_MEMORY_BLOCK_WORDS * 4 * ch_idx;
dev_data->start_address = start_addr_chn;
reg_val = (mem_blocks) << 24;
uint32_t clock_divider = 1;
reg_val |= (clock_divider);
putreg32(reg_val, reg0_addr);
reg_val = 0;
/* use APB clock */
reg_val |= RMT_REF_ALWAYS_ON_CHN;
/* memory block in transmission mode */
reg_val &= ~RMT_MEM_OWNER_CHN;
putreg32(reg_val, reg1_addr);
/* set when the buffer swapping IRQ must be generated */
uint32_t reload_addr = RMT_CHN_TX_LIM_REG(ch_idx);
rmtinfo("Setting thr limit at %08X to %d",
reload_addr, dev_data->reload_thresh);
putreg32(dev_data->reload_thresh, reload_addr);
/* allow direct access to RMT's memory */
modifyreg32(RMT_APB_CONF_REG, 0, BIT(0));
}
else
{
rmtwarn("Be careful on opening this channel multiple times");
}
dev_data->open_count += 1;
ret = OK;
spin_unlock_irqrestore(&parent_dev->lock, flags);
nxsem_post(&dev_data->tx_sem);
return ret;
}
static int rmt_close(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct rmt_dev_channel_s *dev_data = inode->i_private;
FAR struct rmt_dev_s *parent_dev =
(struct rmt_dev_s *)dev_data->parent_dev;
int ret;
irqstate_t flags;
DEBUGASSERT(parent_dev);
nxsem_wait(&dev_data->tx_sem);
flags = spin_lock_irqsave(&parent_dev->lock);
dev_data->open_count -= 1;
ret = OK;
spin_unlock_irqrestore(&parent_dev->lock, flags);
nxsem_post(&dev_data->tx_sem);
return ret;
}
static ssize_t rmt_write(FAR struct file *filep,
FAR const char *data,
size_t len)
{
FAR struct inode *inode = filep->f_inode;
FAR struct rmt_dev_channel_s *dev_data = inode->i_private;
FAR struct rmt_dev_s *parent_dev =
(struct rmt_dev_s *)dev_data->parent_dev;
irqstate_t flags;
size_t len_in_words = len / 4;
DEBUGASSERT(parent_dev);
if (data == NULL || (len_in_words == 0) || (len % 4))
{
return -EINVAL;
}
flags = spin_lock_irqsave(&parent_dev->lock);
/* set RMT's memory as writable */
uint32_t reg1_addr = RMT_CHNCONF1_REG(dev_data->ch_idx);
modifyreg32(reg1_addr, 0, RMT_MEM_RD_RST_CHN);
modifyreg32(reg1_addr, RMT_MEM_RD_RST_CHN, 0);
dev_data->src = (uint32_t *)data;
dev_data->src_offset = 0;
dev_data->words_to_send = len_in_words;
/* enable IRQs for buffer refill and End-of-Transmition (EOT) */
modifyreg32(
RMT_INT_ENA_REG,
0,
RMT_CHN_TX_THR_EVENT_INT_ENA(dev_data->ch_idx) |
RMT_CHN_TX_END_INT_ENA(dev_data->ch_idx));
rmt_load_tx_buffer(dev_data);
/* tell RMT to start the transmition */
modifyreg32(reg1_addr, 0, RMT_TX_START_CHN(dev_data->ch_idx));
spin_unlock_irqrestore(&parent_dev->lock, flags);
/* wait for the transmition to finish */
nxsem_wait(&dev_data->tx_sem);
nxsem_post(&dev_data->tx_sem);
return len;
}
/****************************************************************************
* Name: board_rmt_initialize
*
* Description:
* Initialize and register the RMT driver
*
* Input Parameters:
* devno - The device number, used to build the device path as /dev/rmtN
* rmt_dev - Pointer to the RMT device that will be used
* nleds - number of LEDs
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
static const struct file_operations g_rmt_channel_fops =
{
rmt_open, /* open */
rmt_close, /* close */
NULL, /* read */
rmt_write, /* write */
NULL, /* seek */
NULL, /* ioctl */
};
int board_rmt_initialize(int channel, int output_pin)
{
struct rmt_dev_s *rmt_dev = esp32_rmtinitialize();
DEBUGASSERT(rmt_dev);
char devpath[13];
int ret;
rmt_attach_pin_to_channel(rmt_dev, channel, output_pin);
struct rmt_dev_channel_s *channel_data = &(rmt_dev->channels[channel]);
/* Register the WS2812 driver at the specified location. */
snprintf(devpath, sizeof(devpath), "/dev/rmt%d", channel);
/* Register the character driver */
ret = register_driver(devpath, &g_rmt_channel_fops, 0666, channel_data);
if (ret < 0)
{
rmterr("ERROR: board_rmt_initialize(%s) failed: %d\n",
devpath, ret);
return ret;
}
return OK;
}
#endif

View File

@ -0,0 +1,121 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_ARCH_LEDS is not set
# CONFIG_NSH_ARGCAT is not set
# CONFIG_NSH_CMDOPT_HEXDUMP is not set
CONFIG_ALLOW_BSD_COMPONENTS=y
CONFIG_ARCH="xtensa"
CONFIG_ARCH_BOARD="esp32-devkitc"
CONFIG_ARCH_BOARD_COMMON=y
CONFIG_ARCH_BOARD_ESP32_DEVKITC=y
CONFIG_ARCH_CHIP="esp32"
CONFIG_ARCH_CHIP_ESP32=y
CONFIG_ARCH_CHIP_ESP32WROVER=y
CONFIG_ARCH_INTERRUPTSTACK=2048
CONFIG_ARCH_SETJMP_H=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_XTENSA=y
CONFIG_BOARD_LOOPSPERMSEC=16717
CONFIG_BUILTIN=y
CONFIG_CODECS_HASH_MD5=y
CONFIG_DEBUG_ASSERTIONS=y
CONFIG_DEBUG_FEATURES=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEV_URANDOM=y
CONFIG_DRIVERS_IEEE80211=y
CONFIG_DRIVERS_WIRELESS=y
CONFIG_ESP32_SPIFLASH=y
CONFIG_ESP32_SPIFLASH_SPIFFS=y
CONFIG_ESP32_STORAGE_MTD_SIZE=0x80000
CONFIG_ESP32_UART0=y
CONFIG_ESP32_WIFI=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_EXAMPLES_WEBSERVER=y
CONFIG_FS_PROCFS=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_IDLETHREAD_STACKSIZE=2048
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INIT_STACKSIZE=3072
CONFIG_INTELHEX_BINARY=y
CONFIG_IOB_NBUFFERS=128
CONFIG_MM_REGIONS=4
CONFIG_NAME_MAX=48
CONFIG_NETDB_DNSCLIENT=y
CONFIG_NETDB_DNSCLIENT_NAMESIZE=64
CONFIG_NETDEV_LATEINIT=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NETDEV_WIRELESS_IOCTL=y
CONFIG_NETUTILS_CJSON=y
CONFIG_NETUTILS_CODECS=y
CONFIG_NETUTILS_HTTPD_DIRLIST=y
CONFIG_NETUTILS_HTTPD_SENDFILE=y
CONFIG_NETUTILS_IPERF=y
CONFIG_NETUTILS_NTPCLIENT_STACKSIZE=4096
CONFIG_NETUTILS_TELNETD=y
CONFIG_NETUTILS_WEBCLIENT=y
CONFIG_NETUTILS_WEBSERVER=y
CONFIG_NET_BROADCAST=y
CONFIG_NET_ETH_PKTSIZE=1518
CONFIG_NET_ICMP=y
CONFIG_NET_ICMP_SOCKET=y
CONFIG_NET_STATISTICS=y
CONFIG_NET_TCP=y
CONFIG_NET_TCP_WRITE_BUFFERS=y
CONFIG_NET_UDP=y
CONFIG_NFS=y
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CODECS_BUFSIZE=2048
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_LINELEN=300
CONFIG_NSH_READLINE=y
CONFIG_NSH_WGET_BUFF_SIZE=2048
CONFIG_PREALLOC_TIMERS=4
CONFIG_PTHREAD_MUTEX_TYPES=y
CONFIG_RAM_SIZE=114688
CONFIG_RAM_START=0x20000000
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_RR_INTERVAL=200
CONFIG_RTC=y
CONFIG_RTC_ALARM=y
CONFIG_RTC_DRIVER=y
CONFIG_RTC_NALARMS=2
CONFIG_SCHED_LPWORK=y
CONFIG_SIG_DEFAULT=y
CONFIG_SMP=y
CONFIG_SMP_NCPUS=2
CONFIG_SPI=y
CONFIG_SPIFFS_NAME_MAX=48
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=18
CONFIG_START_MONTH=2
CONFIG_START_YEAR=2021
CONFIG_SYSLOG_BUFFER=y
CONFIG_SYSLOG_TIMESTAMP=y
CONFIG_SYSTEM_DHCPC_RENEW=y
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_NTPC=y
CONFIG_SYSTEM_PING=y
CONFIG_SYSTEM_SYSTEM=y
CONFIG_SYSTEM_TASKSET=y
CONFIG_TESTING_GETPRIME=y
CONFIG_TESTING_OSTEST=y
CONFIG_TESTING_SMP=y
CONFIG_TLS_TASK_NELEM=4
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_WIRELESS=y
CONFIG_WIRELESS_WAPI=y
CONFIG_WIRELESS_WAPI_CMDTOOL=y
CONFIG_WIRELESS_WAPI_INITCONF=y
CONFIG_WIRELESS_WAPI_STACKSIZE=4096
CONFIG_EXPERIMENTAL=y
CONFIG_ESP32_RMT=y
CONFIG_EXAMPLES_WS2812_WITH_ESP32_RMT=y

View File

@ -45,6 +45,10 @@ ifeq ($(CONFIG_USERLED),y)
CSRCS += esp32_userleds.c
endif
ifeq ($(CONFIG_WS2812),y)
CSRCS += esp32_ws2812.c
endif
ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += esp32_buttons.c
endif

View File

@ -66,6 +66,11 @@
#define ONESHOT_TIMER 1
#define ONESHOT_RESOLUTION_US 1
/* RMT gpio */
#define RMT_OUTPUT_PIN 4
#define RMT_CHANNEL 0
/****************************************************************************
* Public Types
****************************************************************************/
@ -201,5 +206,26 @@ int board_i2sdev_initialize(int port, bool enable_tx, bool enable_rx);
int esp32_cs4344_initialize(int port);
#endif
/****************************************************************************
* Name: board_ws2812_initialize
*
* Description:
* This function may called from application-specific logic during its
* to perform board-specific initialization of the ws2812 device
*
*
****************************************************************************/
# ifdef CONFIG_WS2812
# ifndef CONFIG_WS2812_NON_SPI_DRIVER
int board_ws2812_initialize(int devno, int spino, uint16_t nleds);
# else
int board_ws2812_initialize(
int devno,
uint16_t nleds,
void *dev);
# endif
# endif
#endif /* __ASSEMBLY__ */
#endif /* __BOARDS_XTENSA_ESP32_ESP32_DEVKITC_SRC_ESP32_DEVKITC_H */

View File

@ -41,6 +41,7 @@
#endif
#include <nuttx/fs/fs.h>
#include <nuttx/himem/himem.h>
#include <nuttx/board.h>
#if defined(CONFIG_ESP32_EFUSE)
#include "esp32_efuse.h"
@ -152,6 +153,10 @@
# include "esp32_max6675.h"
#endif
#ifdef CONFIG_ESP32_RMT
# include "esp32_rmt.h"
#endif
#include "esp32-devkitc.h"
/****************************************************************************
@ -624,6 +629,14 @@ int esp32_bringup(void)
}
#endif
#ifdef CONFIG_ESP32_RMT
ret = board_rmt_initialize(RMT_CHANNEL, RMT_OUTPUT_PIN);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: board_rmt_initialize() failed: %d\n", ret);
}
#endif
#ifdef CONFIG_RTC_DRIVER
/* Instantiate the ESP32 RTC driver */
@ -644,6 +657,16 @@ int esp32_bringup(void)
ESP32_SPI2, ret);
}
# endif
#endif
#ifdef CONFIG_WS2812
# ifndef CONFIG_WS2812_NON_SPI_DRIVER
ret = board_ws2812_initialize(0, ESP32_SPI3, CONFIG_WS2812_LED_COUNT);
if (ret < 0)
{
syslog(LOG_ERR, "Failed to initialize ws2812 driver\n");
}
# endif
#endif
/* If we got here then perhaps not all initialization was successful, but

View File

@ -0,0 +1,124 @@
/****************************************************************************
* boards/xtensa/esp32/esp32-devkitc/src/esp32_ws2812.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <errno.h>
#include <debug.h>
#include <stdio.h>
#include "xtensa.h"
#include <nuttx/kmalloc.h>
#include <nuttx/spi/spi.h>
#include <nuttx/leds/ws2812.h>
#ifdef CONFIG_WS2812
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define APB_PERIOD (12.5)
#define T0H ((uint16_t)(350 / APB_PERIOD)) // ns
#define T0L ((uint16_t)(900 / APB_PERIOD)) // ns
#define T1H ((uint16_t)(900 / APB_PERIOD)) // ns
#define T1L ((uint16_t)(350 / APB_PERIOD)) // ns
#define RES ((uint16_t)(60000 / APB_PERIOD)) // ns
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
# ifndef CONFIG_WS2812_NON_SPI_DRIVER
/****************************************************************************
* Name: board_ws2812_initialize
*
* Description:
* Initialize and register the WS2812 LED driver.
*
* Input Parameters:
* devno - The device number, used to build the device path as /dev/leddrvN
* spino - SPI port number
* nleds - number of LEDs
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int board_ws2812_initialize(int devno, int spino, uint16_t nleds)
{
struct spi_dev_s *spi;
char devpath[13];
int ret;
spi = esp32_spibus_initialize(spino);
if (spi == NULL)
{
return -ENODEV;
}
/* Register the WS2812 driver at the specified location. */
snprintf(devpath, sizeof(devpath), "/dev/leds%d", devno);
ret = ws2812_leds_register(devpath, spi, nleds);
if (ret < 0)
{
lederr("ERROR: ws2812_leds_register(%s) failed: %d\n",
devpath, ret);
return ret;
}
return OK;
}
# else
int board_ws2812_initialize(int devno, int spino, uint16_t nleds)
{
return -1;
}
# endif
#endif

View File

@ -55,7 +55,11 @@
* Pre-processor Definitions
****************************************************************************/
#ifdef WS2812_HAS_WHITE
# define WS2812_RW_PIXEL_SIZE 4
#else
# define WS2812_RW_PIXEL_SIZE 3
#endif
#ifdef CONFIG_WS2812_NON_SPI_DRIVER

View File

@ -629,6 +629,24 @@
# define rcinfo _none
#endif
#ifdef CONFIG_DEBUG_RMT_ERROR
# define rmterr _err
#else
# define rmterr _none
#endif
#ifdef CONFIG_DEBUG_RMT_WARN
# define rmtwarn _warn
#else
# define rmtwarn _none
#endif
#ifdef CONFIG_DEBUG_RMT_INFO
# define rmtinfo _info
#else
# define rmtinfo _none
#endif
#ifdef CONFIG_DEBUG_RTC_ERROR
# define rtcerr _err
#else