Nuttx驱动(二)实例

接上一篇文章,这篇主要是nuttx驱动编写实践部分。基础部分请移驾《Nuttx驱动(一)简介》

Nuttx驱动例程

在该例程中,假设有这么一个设备:有3个IO输出和一个IO输入的RGB_LED设备,叫slimLED好了。(这里简单点就先不使用PWM控制了

  1. 创建字符设备驱动主体,即文件操作file_operations,然后实现open()close()read()write()ioctl()
  2. 注册该设备驱动到系统中,将会在系统的/dev目录下生成一个名为slimLED的设备节点;
  3. 通过应用程序来获取输入脚状态、控制三个输出脚状态。

1. 驱动框架部分

说明:在nuttx仓库中,实现slimLED这个驱动接口,系统层驱动与具体board无关。后期可以适配不同芯片或不同的board,所以尽可能灵活

要修改如下文件(nuttx仓库)

  • Kconfig
  • Make.defs
  • slimLED.c
  • slimLED.h
Kconfig 配置

用于图形化配置工具的

config SLIM_RGB_LED
	bool "slim RGB led device support"
	default n
	---help---
		Enable driver support for the slim LED controler.

在这里插入图片描述
在这里插入图片描述

Make.defs
# slim RGB LED

ifeq ($(CONFIG_SLIM_RGB_LED), y)
  CSRCS += slimLED.c
endif
slimLED.h
#ifndef __DRIVERS_SLIM_LED_H__
#define __DRIVERS_SLIM_LED_H__

/****************************************************************************
 * Included Files
 ****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>

/****************************************************************************
 * Pre-processor Definitions
 ****************************************************************************/
#define SLEDIOC_SET         0x0001
#define SLEDIOC_GET         0x0002

struct slimled_status_s{
    bool state;
};

struct slimled_param_s{
    short num;
    struct slimled_status_s on;
};

struct slimled_lower_s{
    CODE int (*setio)(FAR struct slimled_lower_s *low, FAR struct slimled_param_s param);
    CODE int (*getio)(FAR struct slimled_lower_s *low, FAR struct slimled_status_s *status);
    CODE int (*ioctl)(FAR struct slimled_lower_s *low, int cmd, unsigned long arg);
};

int slimled_register(FAR const char *path,  FAR void *lower);

#endif
slimLED.c
#include <nuttx/config.h>
#include <stdlib.h>
#include <fixedmath.h>
#include <assert.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/sensors/slimled.h>


#if defined(CONFIG_SLIM_RGB_LED)
/****************************************************************************
 * Private Function Prototypes
 ****************************************************************************/
static int  slimled_open(FAR struct file *filep);
static int  slimled_close(FAR struct file *filep);
static int  slimled_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
static int  slimled_read(FAR struct file *filep, FAR char *buffer, size_t buflen);
static int  slimled_write(FAR struct file *filep, FAR const char *buffer,size_t buflen);

/****************************************************************************
 * Private Data
 ****************************************************************************/
static const struct file_operations slimled_fops = {
    .open   = slimled_open,
    .close  = slimled_close,
    .read   = slimled_read,
    .write  = slimled_write,
    .ioctl  = slimled_ioctl,
};
/****************************************************************************
 * Private Functions
 ****************************************************************************/

/****************************************************************************
 * Name: slimled_ioctl
 ****************************************************************************/
static int  slimled_open(FAR struct file *filep){
    return OK;
}
static int  slimled_close(FAR struct file *filep){
    return OK;
}
static int slimled_read(FAR struct file *filep, FAR char *buffer, size_t buflen){
    return OK;
}
static int slimled_write(FAR struct file *filep, FAR const char *buffer,size_t buflen){
    return OK;
}
static int slimled_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
    FAR struct inode *inode    = filep->f_inode;
    FAR struct slimled_lower_s *lower = inode->i_private;
    int ret = OK;

    switch (cmd)
    {
        case SLEDIOC_SET:{
            FAR struct slimled_param_s param = {0};
            param.num = arg & 0xFF;
            param.on.state = (arg >> 8) & 0x03;
            ret = lower->setio(lower, param);
            break;
        }
        case SLEDIOC_GET:{
            FAR struct slimled_status_s *ptr = (FAR struct slimled_status_s*)((uintptr_t)arg);
            DEBUGASSERT(ptr != NULL);
            ret = lower->getio(lower, ptr);
            break;
        }
        default:
            ret = lower->ioctl(lower, cmd, arg);
        break;
    }
    return ret;
}

/****************************************************************************
 * Public Functions
 ****************************************************************************/

/****************************************************************************
 * Name: slimled_register
 ****************************************************************************/

int slimled_register(FAR const char *path, FAR struct slimled_lower_s *dev,
                      FAR void *lower)
{
    int ret;

    DEBUGASSERT(path != NULL);
    DEBUGASSERT(lower != NULL);

    /* Register the slimled character driver */
    ret = register_driver(path, &slimled_fops, 0666, lower);
    if (ret < 0){
        _err("ERROR: Failed to register slim led driver: %d\n", ret);
    }

    return ret;
}

2. board适配层

说明:在芯片级或 board 级仓库中,实现 slimLED 这个设备驱动,与具体的 芯片平台 或 board平台 进行绑定。构建设备驱动程序与硬件直接的桥梁

要修改如下文件(board仓库)

  • Make.defs
  • configs/nsh/defconfig
  • board_def.h
  • bringup.c
  • platform_data.c
  • board_slimLED.h
  • board_slimLED.c
Make.defs
ifeq ($(CONFIG_SLIM_RGB_LED),y)
CSRCS += board_slimled.c
endif
defconfig
CONFIG_SLIM_RGB_LED=y
board_def.h

定义对应的IO口,以Apollo芯片为例

#define SLIM_LED_R        (GPIO_PIN1 | GPIO_FUN_GPIO | GPIO_DRIVESTRENGTH_0P5X | GPIO_OUTCFG_PUSHPULL)
#define SLIM_LED_G        (GPIO_PIN2 | GPIO_FUN_GPIO | GPIO_DRIVESTRENGTH_0P5X | GPIO_OUTCFG_PUSHPULL)
#define SLIM_LED_B        (GPIO_PIN3 | GPIO_FUN_GPIO | GPIO_DRIVESTRENGTH_0P5X | GPIO_OUTCFG_PUSHPULL)
#define SLIM_STA          (GPIO_PIN4 | GPIO_FUN_GPIO | GPIO_OUTCFG_DISABLE | GPIO_INPUT_ENABLE | GPIO_INTDIR_HI2LO)
bringup.c

初始化slim led设备,设备名和设备操作函数绑定及其初始化

int board_bringup(void){
	...
#ifdef CONFIG_SLIM_RGB_LED
  ret = board_slimled_initialize("/dev/slimled", &slimled_pdata, eLED_CNT);
  if(ret < 0){
    printf("ERROR: slim led driver initialize failed: %d\n", ret);
  }
#endif
	...
}
platform_data.c
const struct slimled_platform_data slimled_pdata[] = {
    {
      .pin   = SLIM_LED_R,
      .state = false,
    },
    {
      .pin   = SLIM_LED_G,
      .state = false,
    },
    {
      .pin   = SLIM_LED_B,
      .state = false,
    },
};
board_slimLED.h
#ifndef __BOARD_SLIMLED_H__
#define __BOARD_SLIMLED_H__

#include <nuttx/config.h>
#include <nuttx/regulator/fixed-regulator.h>

typedef enum{
    eLED_R,
    eLED_G,
    eLED_B,
    eLED_CNT,
}slimled_Num;

struct slimled_platform_data{
    uint32_t pin;
    bool     state;
};

extern const struct slimled_platform_data slimled_pdata[];
int board_slimled_initialize(const char *devpath, const struct slimled_platform_data *pdata, uint32_t cnt);

#endif
board_slimLED.c
#include <nuttx/nuttx.h>
#include <nuttx/irq.h>
#include <nuttx/signal.h>
#include <debug.h>
#include <assert.h>
#include <errno.h>

#include <nuttx/err.h>
#include "board_def.h"
#include "board_slimLED.h"
#include <slimLED.h>

#ifdef CONFIG_SLIM_RGB_LED

static bool _get_slimled_state(void);
static void _set_slimled_param(FAR const struct slimled_lower_s *lower, FAR struct slimled_param_s param);

static const struct slimled_lower_s slimled_lower = {
    .getio = _get_slimled_state,
    .setio = _set_slimled_param,
    .ioctl = _set_slimled_param,
};


/****************************************************************************
 * Private Functions
 ****************************************************************************/
static bool _get_slimled_state(void){
    return gpioread(SLIM_STA);
}

static void _set_slimled_param(const struct slimled_lower_s *lower, struct slimled_param_s param){
    printf("%s %d %d\r\n", __func__, param.num, param.on.state);

    if(param.num < eLED_CNT){
        gpiowrite(slimled_pdata[param.num].pin, param.on.state);
    }
}

int board_slimled_initialize(const char *devpath, const struct slimled_platform_data *pdata, uint32_t cnt){
    if(cnt > eLED_CNT){
        printf("ERROR: slim led cnt setting error...\n");
        cnt = eLED_CNT;
    }
    for(uint8_t i=0;i<cnt;i++){
        configgpio(pdata[i].pin);
    }
    configgpio(SLIM_STA);

    return slimled_register(devpath, &slimled_lower);
}

#endif

3. 应用层

这里直接创建 slim led 应用线程

#include <stdio.h>
#include <stdbool.h>
#include <sys/types.h>
#include <fcntl.h>
#include <pthread.h>
#include <nuttx/config.h>
#include <nuttx/analog/ioctl.h>
#include <slimLED.h>
#include <syslog.h>

typedef enum{
    eCHANNEL_LED_R,
    eCHANNEL_LED_G,
    eCHANNEL_LED_B,
    eCHANNEL_LED_CNT,
}slimled_channelTypeDef;
static int led_fd = -1;

static bool _slimled_init(void){
    led_fd = open("/dev/slimled", O_WRONLY);
    if(led_fd < 0){
        printf("slimled open failed\n");
        return false;
    }
    return true;
}

static bool _set_slimled_channal(slimled_channelTypeDef channel){
    struct slimled_param_s tmp[eCHANNEL_LED_CNT] = {0};

    if(channel > eCHANNEL_LED_CNT){
        printf("param setting error...\n");
        return false;
    }
    if(led_fd < 0){
        printf("slimled not opened yet\n");
        return _slimled_init();
    }
    for(uint8_t i=0;i<eCHANNEL_LED_CNT;i++){
        tmp[i].num = i;
        if(i == channel){
            tmp[i].on.state = true;
        }else{
            tmp[i].on.state = false;
        }
        ioctl(led_fd, SLEDIOC_SET, tmp[i]);
    }
}


void *slimled_Thread(void *arg){
    struct slimled_param_s slimled[3] = {0};
    int ret = 0;
    int sta = 0;

    if(false == _slimled_init()){
        return;
    }

    for(;;){
        for(uint8_t i=0;i<eCHANNEL_LED_CNT;i++){
            _set_slimled_channal(i);
            sleep(5);
        }
        ioctl(led_fd, TLEDIOC_GET, &sta);
        printf("= = == ioctl state: %d get IO state:%d= == =\n\n\n", ret, sta);
	}
    close(led_fd);
    return;
}
— 完 —
  • 4
    点赞
  • 12
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值