这些小活动你都参加了吗?快来围观一下吧!>>
电子产品世界 » 论坛首页 » DIY与开源设计 » 电子DIY » 【i646593001】两轮子平衡小车DIY 进程帖

共17条 2/2 1 2 跳转至
助工
2015-06-19 14:18:30     打赏
11楼

MPU6050驱动实验


   这个实验花了一周多的时间,总结一下,首先决定用DMP处理,这样省略了数据融合部分,且DMP的处理速度可以到200Hz,完全达到性能要求,关键还是经过DMP处理的数据结果比较精确。查找资料知道DMP的驱动有6.0版的,下载该版本驱动后,驱动的ReleaseNote说:

   所以下载了5.1.2的驱动,发现开发者使用的驱动就是用这个驱动移植过来的。当然还有别的驱动程序,比如CrazePony四轴飞行器里,也是采用MPU6050的驱动,就和5.1.2版本的不太一样。

    决定使用5.1.2版的驱动,一是自己根据驱动重写函数,因为自己的i2c库函数名不太一样。搞了好几天也没弄出来,只好拿作者的文件用了,把作者的i2c函数换成自己程序中使用的i2c函数。终于调试成功,测试发现每隔十几秒可能会出现一次fifo读取错误,具体函数是mpu_read_fifo_stream(),问题不大,具体原因没有细查。随着读取时间间隔的不同,出错的概率也不同,在每2ms读取一次时出错的概率是最低的,在10s以上会出一次,周期还比较固定

    下面来张静止状态的输出截图,可以看出数据很稳定,误差在1/1000以内:

    来个插图,使用原作者提供的函数,读取 数据的程序。第一个任务是每2ms读取一次DMP数据,第二个任务是每隔200ms输出一次倾角数据。


助工
2015-07-09 00:17:42     打赏
12楼

蓝牙的连接实验

    电路图中将蓝牙串口模块接到了USART3上,如下图所示。注意下图的UART-TX及UART-RX表示的是蓝牙模块的发送端口和接收端口,PB10为stm32的TX,接到蓝牙的RX上。



    只需要配置好USART3,就可以从该端口接收蓝牙的数据了,不用管蓝牙具体的工作方式及配置等,只需要使用手机客户端连接到该蓝牙模块即可。

    蓝牙模块在这里就相当于两根导线,从小车的USART3连接到手机的串口上,连线的过程就是蓝牙配对连接的过程。

    程序比较简单,直接贴代码,使用库函数配置,初始化的代码及中断函数可以直接使用。任务程序只是一个测试接收数据的任务。

/**
 * uart3.c - uart3 bluetooth functions
 */
#include 
#include 

/*ST includes */
#include "stm32f10x.h"

/*FreeRtos includes*/
#include "FreeRTOS.h"
#include "task.h"
#include "semphr.h"

#define UART3_PERIF      RCC_APB1Periph_USART3

#define UART3_GPIO_PERIF RCC_APB2Periph_GPIOB
#define UART3_GPIO_TX    GPIO_Pin_10
#define UART3_GPIO_RX    GPIO_Pin_11

xQueueHandle      uart3RxQueue;

void uart3Init(void)
{

  USART_InitTypeDef USART_InitStructure;
  GPIO_InitTypeDef GPIO_InitStructure;
  NVIC_InitTypeDef NVIC_InitStructure;
	
  /* Enable GPIO and USART clock */
	RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
	RCC_APB1PeriphClockCmd(UART3_PERIF, ENABLE);

  GPIO_InitStructure.GPIO_Pin   = UART3_GPIO_RX;
  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_IN_FLOATING;
  GPIO_Init(GPIOB, &GPIO_InitStructure);

  GPIO_InitStructure.GPIO_Pin   = UART3_GPIO_TX;
  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_AF_PP;
  GPIO_Init(GPIOB, &GPIO_InitStructure);

  USART_InitStructure.USART_BaudRate            = 9600;
  USART_InitStructure.USART_Mode                = USART_Mode_Rx | USART_Mode_Tx;
  USART_InitStructure.USART_WordLength          = USART_WordLength_8b;
  USART_InitStructure.USART_StopBits            = USART_StopBits_1;
  USART_InitStructure.USART_Parity              = USART_Parity_No ;
  USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
  USART_Init(USART3, &USART_InitStructure);

  USART_ITConfig(USART3,USART_IT_RXNE,ENABLE);

  NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
  NVIC_Init(&NVIC_InitStructure);

  USART_Cmd(USART3, ENABLE);
}

void uart3RxHandler(void)
{
  unsigned char Uart3_Rx;
  portBASE_TYPE xHigherPriorityTaskWoken;
	
  if(USART_GetITStatus(USART3,USART_IT_RXNE))
  {
    Uart3_Rx = USART_ReceiveData(USART3);
    xQueueSendFromISR(uart3RxQueue, &Uart3_Rx, &xHigherPriorityTaskWoken);
    USART_ClearITPendingBit(USART3,USART_FLAG_TC);
		return;
  }
}

void bluetoothInit(void)
{
  uart3Init();
	uart3RxQueue = xQueueCreate(3, 1);
	printf("Bluetooth initialized \r\n");
}

void receiveBluetooth(unsigned char *ch)
{
  xQueueReceive(uart3RxQueue,ch,portMAX_DELAY);
}

void vBluetoothTestTask( void *pvParameters )
{
	unsigned char bt;
  for( ;; )
  {
		receiveBluetooth(&bt);
		printf("UART3 Received %02x\r\n",bt);
  }
}





助工
2015-07-13 13:40:29     打赏
13楼

NRF24L01P通信

    这几天一直在调试nrf24l01p的通信,终于调通了:

控制器使用的是上次活动时买的烈火四轴飞行器的遥控器:


    由于采用了freeRTOS系统,采用任务调度方式,同时管脚多,一粗心设错了就调不通。在小车上就因为SPI的中断调用函数放错了位置,用了很多时间才找出来。今天把代码贴上,省得以后再重复调。下面是遥控器的代码,每秒发送一次hello消息。有些函数用不多,例如receivePacket等,写上以备后用。

/*
 * nrf24l01.c: nRF24L01(-p) TX mode low level driver
 */

/* TODO:
 *  - Separate the SPI and GPIO driver from here.
 *  - Handle TX mode
 */

#include "stdio.h"
#include <stdbool.h>
#include <string.h>

#include "nrf24l01.h"

#include "stm32f10x_conf.h"
#include "stm32f10x_rcc.h"
#include "stm32f10x_spi.h"
#include "stm32f10x_exti.h"

/*FreeRtos includes*/
#include "FreeRTOS.h"
#include "task.h"
#include "semphr.h"
#include "queue.h"

/* Defines for the SPI and GPIO pins used to drive the SPI Flash */
#define RADIO_GPIO_CS             GPIO_Pin_13
#define RADIO_GPIO_CS_PORT        GPIOC
#define RADIO_GPIO_CS_PERIF       RCC_APB2Periph_GPIOC

#define RADIO_GPIO_CE             GPIO_Pin_14
#define RADIO_GPIO_CE_PORT        GPIOC
#define RADIO_GPIO_CE_PERIF       RCC_APB2Periph_GPIOC

#define RADIO_GPIO_IRQ            GPIO_Pin_15
#define RADIO_GPIO_IRQ_PORT       GPIOC
#define RADIO_GPIO_IRQ_PERIF      RCC_APB2Periph_GPIOC
#define RADIO_GPIO_IRQ_SRC_PORT   GPIO_PortSourceGPIOC
#define RADIO_GPIO_IRQ_SRC        GPIO_PinSource15
#define RADIO_GPIO_IRQ_LINE       EXTI_Line15

#define RADIO_SPI                 SPI2
#define RADIO_SPI_CLK             RCC_APB1Periph_SPI2
#define RADIO_GPIO_SPI_PORT       GPIOB
#define RADIO_GPIO_SPI_SCK        GPIO_Pin_13
#define RADIO_GPIO_SPI_MISO       GPIO_Pin_14
#define RADIO_GPIO_SPI_MOSI       GPIO_Pin_15

#define NVIC_RADIO_PRI        13

/* Registers address definition */
#define REG_CONFIG      0x00  // 'Config' register address
#define REG_EN_AA       0x01  // 'Enable Auto Acknowledgment' register address
#define REG_EN_RXADDR   0x02  // 'Enabled RX addresses' register address
#define REG_SETUP_AW    0x03  // 'Setup address width' register address
#define REG_SETUP_RETR  0x04  // 'Setup Auto. Retrans' register address
#define REG_RF_CH       0x05  // 'RF channel' register address
#define REG_RF_SETUP    0x06  // 'RF setup' register address
#define REG_STATUS      0x07  // 'Status' register address
#define REG_OBSERVE_TX  0x08  // 'Observe TX' register address
#define REG_RPD         0x09  // 'Carrier Detect' register address
#define REG_RX_ADDR_P0  0x0A  // 'RX address pipe0' register address
#define REG_RX_ADDR_P1  0x0B  // 'RX address pipe1' register address
#define REG_RX_ADDR_P2  0x0C  // 'RX address pipe2' register address
#define REG_RX_ADDR_P3  0x0D  // 'RX address pipe3' register address
#define REG_RX_ADDR_P4  0x0E  // 'RX address pipe4' register address
#define REG_RX_ADDR_P5  0x0F  // 'RX address pipe5' register address
#define REG_TX_ADDR     0x10  // 'TX address' register address
#define REG_RX_PW_P0    0x11  // 'RX payload width, pipe0' register address
#define REG_RX_PW_P1    0x12  // 'RX payload width, pipe1' register address
#define REG_RX_PW_P2    0x13  // 'RX payload width, pipe2' register address
#define REG_RX_PW_P3    0x14  // 'RX payload width, pipe3' register address
#define REG_RX_PW_P4    0x15  // 'RX payload width, pipe4' register address
#define REG_RX_PW_P5    0x16  // 'RX payload width, pipe5' register address
#define REG_FIFO_STATUS 0x17  // 'FIFO Status Register' register address
#define REG_DYNPD       0x1C
#define REG_FEATURE     0x1D

#define VAL_RF_SETUP_250K 0x26
#define VAL_RF_SETUP_1M   0x06
#define VAL_RF_SETUP_2M   0x0E

#define VAL_SETUP_AW_3B 1
#define VAL_SETUP_AW_4B 2
#define VAL_SETUP_AW_5B 3

/* nRF24L SPI commands */
#define CMD_R_REG              0x00
#define CMD_W_REG              0x20
#define CMD_R_RX_PAYLOAD       0x61
#define CMD_W_TX_PAYLOAD       0xA0
#define CMD_FLUSH_TX           0xE1
#define CMD_FLUSH_RX           0xE2
#define CMD_REUSE_TX_PL        0xE3
#define CMD_ACTIVATE           0x50
#define CMD_RX_PL_WID          0x60
#define CMD_W_ACK_PAYLOAD(P)  (0xA8|(P&0x0F))
#define CMD_W_PAYLOAD_NO_ACK   0xD0
#define CMD_NOP                0xFF

#define ACTIVATE_DATA   0x73
#define DUMMY_BYTE    0xA5

#define RADIO_PACKET_SIZE 32

#define RADIO_CONNECTED_TIMEOUT   (2000)

/*** Defines ***/
#define RADIO_RATE_250K 0
#define RADIO_RATE_1M   1
#define RADIO_RATE_2M   2

/* Usefull macro */
#define RADIO_EN_CS()  GPIO_ResetBits(RADIO_GPIO_CS_PORT, RADIO_GPIO_CS)
#define RADIO_DIS_CS() GPIO_SetBits(RADIO_GPIO_CS_PORT, RADIO_GPIO_CS)
#define RADIO_DIS_CE() GPIO_ResetBits(RADIO_GPIO_CE_PORT, RADIO_GPIO_CE)
#define RADIO_EN_CE()  GPIO_SetBits(RADIO_GPIO_CE_PORT, RADIO_GPIO_CE)

/* Synchronisation */
xSemaphoreHandle dataRdy;
xQueueHandle txQueue;
xQueueHandle rxQueue;


typedef struct _radioPacket
{
  char raw[RADIO_PACKET_SIZE];
} radioPacket;
static uint32_t lastPacketTick;

static bool radioIsInit;

/***********************
 * SPI private methods *
 ***********************/
static char spiSendByte(char byte)
{
  /* Loop while DR register in not emplty */
  while (SPI_I2S_GetFlagStatus(RADIO_SPI, SPI_I2S_FLAG_TXE) == RESET);

  /* Send byte through the SPI1 peripheral */
  SPI_I2S_SendData(RADIO_SPI, byte);

  /* Wait to receive a byte */
  while (SPI_I2S_GetFlagStatus(RADIO_SPI, SPI_I2S_FLAG_RXNE) == RESET);

  /* Return the byte read from the SPI bus */
  return SPI_I2S_ReceiveData(RADIO_SPI);
}

static char spiReceiveByte()
{
  return spiSendByte(DUMMY_BYTE);
}

/****************************************************************
 * nRF SPI commands, Every commands return the status byte      *
 ****************************************************************/

/* Read len bytes from a nRF24L register. 5 Bytes max */
unsigned char nrfReadReg(unsigned char address, char *buffer, int len)
{
  unsigned char status;
  int i;

  RADIO_EN_CS();

  /* Send the read command with the address */
  status = spiSendByte( CMD_R_REG | (address&0x1F) );
  /* Read LEN bytes */
  for(i=0; i<len; i++)
    buffer[i]=spiReceiveByte();

  RADIO_DIS_CS();

  return status;
}

/* Write len bytes a nRF24L register. 5 Bytes max */
unsigned char nrfWriteReg(unsigned char address, char *buffer, int len)
{
  unsigned char status;
  int i;

  RADIO_EN_CS();

  /* Send the write command with the address */
  status = spiSendByte( CMD_W_REG | (address&0x1F) );
  /* Write LEN bytes */
  for(i=0; i<len; i++)
    spiSendByte(buffer[i]);

  RADIO_DIS_CS();

  return status;
}

/* Write only one byte (useful for most of the reg.) */
unsigned char nrfWrite1Reg(unsigned char address, char byte)
{
  return nrfWriteReg(address, &byte, 1);
}

/* Read only one byte (useful for most of the reg.) */
unsigned char nrfRead1Reg(unsigned char address) {
  char byte;

  nrfReadReg(address, &byte, 1);

  return byte;
}

/* Sent the NOP command. Used to get the status byte */
unsigned char nrfNop()
{
  unsigned char status;

  RADIO_EN_CS();
  status = spiSendByte(CMD_NOP);
  RADIO_DIS_CS();

  return status;
}

unsigned char nrfFlushRx()
{
  unsigned char status;

  RADIO_EN_CS();
  status = spiSendByte(CMD_FLUSH_RX);
  RADIO_DIS_CS();

  return status;
}

unsigned char nrfFlushTx()
{
  unsigned char status;

  RADIO_EN_CS();
  status = spiSendByte(CMD_FLUSH_TX);
  RADIO_DIS_CS();

  return status;
}

// Return the payload length
unsigned char nrfRxLength(unsigned int pipe)
{
  unsigned char length;

  RADIO_EN_CS();
  spiSendByte(CMD_RX_PL_WID);
  length = spiReceiveByte();
  RADIO_DIS_CS();

  return length;
}

unsigned char nrfActivate()
{
  unsigned char status;
  
  RADIO_EN_CS();
  status = spiSendByte(CMD_ACTIVATE);
  spiSendByte(ACTIVATE_DATA);
  RADIO_DIS_CS();

  return status;
}

// Write the ack payload of the pipe 0
unsigned char nrfWriteTx(char *buffer, int len)
{
  unsigned char status;
  int i;

  RADIO_EN_CS();

  /* Send the read command with the address */
  status = spiSendByte(CMD_W_TX_PAYLOAD);
  /* Read LEN bytes */
  for(i=0; i<len; i++)
    spiSendByte(buffer[i]);

  RADIO_DIS_CS();

  return status;
}

// Write the ack payload of the pipe 0
unsigned char nrfWriteAck(unsigned int pipe, char *buffer, int len)
{
  unsigned char status;
  int i;

  printf("send: %s",buffer);
  RADIO_EN_CS();

  /* Send the read command with the address */
  status = spiSendByte(CMD_W_ACK_PAYLOAD(pipe));
//  status = spiSendByte(0xA8);
  /* Read LEN bytes */
  for(i=0; i<len; i++)
    spiSendByte(buffer[i]);

  RADIO_DIS_CS();

  return status;
}

// Read the RX payload
unsigned char nrfReadRX(char *buffer, int len)
{
  unsigned char status;
  int i;

  RADIO_EN_CS();

  /* Send the read command with the address */
  status = spiSendByte(CMD_R_RX_PAYLOAD);
  /* Read LEN bytes */
  for(i=0; i<len; i++)
    buffer[i]=spiReceiveByte();

  RADIO_DIS_CS();

  return status;
}

void nrfSetChannel(unsigned int channel)
{
  if (channel<126)
    nrfWrite1Reg(REG_RF_CH, channel);
}

void nrfSetDatarate(int datarate)
{
  switch(datarate)
  {
    case RADIO_RATE_250K:
      nrfWrite1Reg(REG_RF_SETUP, VAL_RF_SETUP_250K);
      break;
    case RADIO_RATE_1M:
      nrfWrite1Reg(REG_RF_SETUP, VAL_RF_SETUP_1M);
      break;
    case RADIO_RATE_2M:
      nrfWrite1Reg(REG_RF_SETUP, VAL_RF_SETUP_2M);
      break;
  }  
}

void nrfSetAddress(unsigned int pipe, char* address)
{
  int len = 5;

//  ASSERT(pipe<6);

  if (pipe > 1)
    len = 1;

  nrfWriteReg(REG_RX_ADDR_P0 + pipe, address, len);
}

void nrfSetEnable(bool enable)
{
  if (enable)
  {
    RADIO_EN_CE();
  } 
  else
  {
    RADIO_DIS_CE();
  }
}

unsigned char nrfGetStatus()
{
  return nrfNop();
}

bool nrfInterruptActive(void)
{
  return (GPIO_ReadInputDataBit(RADIO_GPIO_IRQ_PORT, RADIO_GPIO_IRQ) == Bit_RESET);
}

/* Initialisation */
void nrfInit(void)
{
  SPI_InitTypeDef  SPI_InitStructure;
  EXTI_InitTypeDef EXTI_InitStructure;
  GPIO_InitTypeDef GPIO_InitStructure;
  NVIC_InitTypeDef NVIC_InitStructure;

  /* Enable SPI and GPIO clocks */
  RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO |RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC,ENABLE);

  /* Enable SPI and GPIO clocks */
  RCC_APB1PeriphClockCmd(RADIO_SPI_CLK, ENABLE);

  /* Configure SPI pins: SCK, MOSI, MISO */
  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_SPI_SCK 
                    |RADIO_GPIO_SPI_MOSI| RADIO_GPIO_SPI_MISO;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
  GPIO_Init(RADIO_GPIO_SPI_PORT, &GPIO_InitStructure);

  /* Configure I/O for the Chip select */
  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_CS;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
  GPIO_Init(RADIO_GPIO_CS_PORT, &GPIO_InitStructure);

  /* Configure I/O for the Chip Enable */
  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_CE;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
  GPIO_Init(RADIO_GPIO_CE_PORT, &GPIO_InitStructure);

  /* Enable SYSCFG clock */
//  RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
  
  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_IRQ;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
  GPIO_Init(RADIO_GPIO_IRQ_PORT, &GPIO_InitStructure);

  /* SPI configuration */
  SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
  SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
  SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
  SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
  SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
  SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
  SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
  SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
  SPI_InitStructure.SPI_CRCPolynomial = 7;
  SPI_Init(RADIO_SPI, &SPI_InitStructure);

  GPIO_EXTILineConfig(RADIO_GPIO_IRQ_SRC_PORT, RADIO_GPIO_IRQ_SRC);
  EXTI_InitStructure.EXTI_Line = RADIO_GPIO_IRQ_LINE;
  EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
  EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
  EXTI_InitStructure.EXTI_LineCmd = ENABLE;
  EXTI_Init(&EXTI_InitStructure);

  /* disable the chip select */
  RADIO_DIS_CS();
  /* disable the chip enable */
  RADIO_DIS_CE();

  NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_RADIO_PRI;
  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
  NVIC_Init(&NVIC_InitStructure);

  /* Enable the SPI  */
  SPI_Cmd(RADIO_SPI, ENABLE);
  
}

u8 Nrf24l01_Check(void)
{ 
  char buf1[5]={0};
  char radioAddress[5] = {0xE1, 0xE2, 0xE3, 0xE4, 0xE5};
  u8 i; 
	
  nrfWriteReg(0x30,radioAddress,5); 
  nrfReadReg(REG_TX_ADDR,buf1,5); 
  for(i=0;i<5;i++) 
  { 
    if(buf1[i]!=radioAddress[i]) 
      break; 
  } 
  if(i==5)
    return SUCCESS ;
  else
    return ERROR ;
}


//not used in TX mode
void nrfInterruptHandler(void)
{
  portBASE_TYPE  xHigherPriorityTaskWoken = pdFALSE;

  if(EXTI_GetITStatus(RADIO_GPIO_IRQ_LINE) != RESET)
  {
    //To unlock RadioTask
    xSemaphoreGiveFromISR(dataRdy, &xHigherPriorityTaskWoken);

    if(xHigherPriorityTaskWoken == pdTRUE)
      portYIELD();

    EXTI_ClearITPendingBit(RADIO_GPIO_IRQ_LINE);
  }

}

/*  Crazyflie  */
void nrfConfigure(void)
{
  int i;
  char radioAddress[5] = {0xE1, 0xE2, 0xE3, 0xE4, 0xE5};

  //Set radio address
  nrfSetAddress(0, radioAddress);
  //Set the radio channel
  nrfSetChannel(40);
  //Set the radio data rate 2M
  nrfSetDatarate(2);
	
  nrfWrite1Reg(REG_EN_RXADDR,0x01);//1
  nrfWrite1Reg(REG_EN_AA,0x01);
  //address length
  nrfWrite1Reg(REG_SETUP_AW,3);
	
  nrfWriteReg(REG_TX_ADDR,radioAddress,5);
  nrfWrite1Reg(REG_SETUP_RETR,0x0);
  nrfWrite1Reg(REG_STATUS,0xfe);
	
  //Power the radio, Enable the DS interruption, set the radio in PRX mode
  nrfWrite1Reg(REG_CONFIG, 0x0e);

  // Enable the dynamic payload size and the ack payload for the pipe 0
  nrfWrite1Reg(REG_FEATURE, 0x06);
  nrfWrite1Reg(REG_DYNPD, 0x01);
  

  //Flush TX
  for(i=0;i<3;i++)
    nrfFlushTx();
  printf("radiolink initNRF24L01 over\r\n");
}

void radiolinkTask(void *param)
{
  unsigned char dataLen;
  static radioPacket p;

  while (1)
  {

//    xSemaphoreTake(dataRdy, portMAX_DELAY);
    lastPacketTick = xTaskGetTickCount();

    nrfSetEnable(false);

    //Fetch all the data (Loop until the RX Fifo is NOT empty)
    while( !(nrfRead1Reg(REG_FIFO_STATUS)&0x01) )
    {
      dataLen = nrfRxLength(0);

      if (dataLen>RADIO_PACKET_SIZE)          //If a packet has a wrong size it is dropped
        nrfFlushRx();
      else                     //Else, it is processed
      {
        nrfReadRX(p.raw, dataLen);
        xQueueSend( rxQueue, &p, 0);
      }
    }
		
    //Push the data to send (Loop until the TX Fifo is full or there is no more data to send)
    while( (uxQueueMessagesWaiting((xQueueHandle)txQueue) > 0) && !(nrfRead1Reg(REG_FIFO_STATUS)&0x20) )
    {
      xQueueReceive(txQueue, &p, 0);
      nrfWriteAck(0,p.raw, RADIO_PACKET_SIZE);
      printf("nrfWriteAck over\r\n");
    }

    //clear the interruptions flags
    nrfWrite1Reg(REG_STATUS, 0x70);
    //Re-enable the radio
    nrfSetEnable(true);
  }
}

void radiolinkTest(void)
{
  if( Nrf24l01_Check() == SUCCESS){
    printf("Nrf24l01 Check returns SUCCESS\r\n");
  }else{
    printf("Nrf24l01 Check returns ERROR\r\n");
  }
  return;
}

/*
 * Public functions,
 * finish all the nrf24l01 iniaialization.
 */

void radiolinkInit()
{
  if(radioIsInit)
    return;

  /* Initialise the semaphores */
  vSemaphoreCreateBinary(dataRdy);

  /* Queue init */
  txQueue = xQueueCreate(3, sizeof(radioPacket));
  rxQueue = xQueueCreate(3,  sizeof(radioPacket));
  
  nrfInit();
  radiolinkTest();
  nrfConfigure();

  /* Start Tx tasks */
  xTaskCreate(radiolinkTask, (const signed char *)"radiolinkTask",
              configMINIMAL_STACK_SIZE, NULL, /*priority*/2, NULL);

  vTaskSetApplicationTaskTag(0, (pdTASK_HOOK_CODE)TASK_RADIO_ID_NBR);

  radioIsInit = true;
}

void radiolinkReInit(void)
{
  if (!radioIsInit)
    return;

  nrfConfigure();
}

/*public functions*/
int sendPacket(unsigned char *p)
{
  xQueueSend(txQueue, p, 0);
  return 0;
}

int receivePacket(unsigned char * pk)
{
  xQueueReceive( rxQueue, pk, portMAX_DELAY);
  return 0;
}

void radioTestTask(void *param)
{
  
  unsigned char buff[RADIO_PACKET_SIZE] = "Hello,this is controller\r\n";  

  while(1)
  {
    vTaskDelay(1000);//send a hello message one time in a second
    sendPacket(buff);
  }
}

 


助工
2015-07-13 13:54:47     打赏
14楼

NRF24L01P通信

    上面贴了遥控器(发送端)的代码,这里贴接收端的代码。nrf芯片接收到消息后产生中断,中断响应函数产生一个dataReady信号量,radiolinkTask任务捕获这个信号量然后通过SPI读取收到的信息。初步目标是通过遥控器的三个旋钮调试PID参数,用一个摇杆控制前后和转向,还有两个按键和一个摇杆,等后续功能开发。程序中如有需要改动/不完善的地方请指教。

/*
 * nrf24l01.c: nRF24L01(-p) PRX mode low level driver
 */

/* TODO:
 *  - Separate the SPI and GPIO driver from here.
 *  - Handle PTX mode
 */

#include "nrf24l01.h"

#include <stdbool.h>
#include <string.h>
#include "stdio.h"

#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
#include "semphr.h"

//#include "utils/cfassert.h"

#include "stm32f10x_conf.h"
#include "stm32f10x_rcc.h"
#include "stm32f10x_spi.h"
#include "stm32f10x_exti.h"

/* Defines for the SPI and GPIO pins used to drive the SPI Flash */
#define RADIO_SPI                 SPI1
#define RADIO_SPI_CLK             RCC_APB2Periph_SPI1
#define RADIO_GPIO_SPI_PORT       GPIOA
#define RADIO_GPIO_SPI_CLK        RCC_APB2Periph_GPIOA
#define RADIO_GPIO_SPI_SCK        GPIO_Pin_5
#define RADIO_GPIO_SPI_MISO       GPIO_Pin_6
#define RADIO_GPIO_SPI_MOSI       GPIO_Pin_7

//PB3/JTDO
#define RADIO_GPIO_CS_PERIF       RCC_APB2Periph_GPIOB
#define RADIO_GPIO_CS_PORT        GPIOB
#define RADIO_GPIO_CS             GPIO_Pin_3

//PA15/JTDI
#define RADIO_GPIO_CE_PERIF       RCC_APB2Periph_GPIOA
#define RADIO_GPIO_CE_PORT        GPIOA
#define RADIO_GPIO_CE             GPIO_Pin_15

//PB4/JNTRST
#define RADIO_GPIO_IRQ_PERIF      RCC_APB2Periph_GPIOB
#define RADIO_GPIO_IRQ_PORT       GPIOB
#define RADIO_GPIO_IRQ            GPIO_Pin_4
#define RADIO_GPIO_IRQ_SRC_PORT   GPIO_PortSourceGPIOB
#define RADIO_GPIO_IRQ_SRC        GPIO_PinSource4
#define RADIO_GPIO_IRQ_LINE       EXTI_Line4

#define DUMMY_BYTE    0xA5

#define NVIC_RADIO_PRI        13

/*** Defines ***/
#define RADIO_RATE_250K 0
#define RADIO_RATE_1M 1
#define RADIO_RATE_2M 2

/* Registers address definition */
#define REG_CONFIG     0x00
#define REG_EN_AA      0x01
#define REG_EN_RXADDR  0x02
#define REG_SETUP_AW   0x03
#define REG_SETUP_RETR 0x04
#define REG_RF_CH      0x05
#define REG_RF_SETUP   0x06
#define REG_STATUS     0x07
#define REG_OBSERVE_TX 0x08
#define REG_RPD        0x09
#define REG_RX_ADDR_P0 0x0A
#define REG_RX_ADDR_P1 0x0B
#define REG_RX_ADDR_P2 0x0C
#define REG_RX_ADDR_P3 0x0D
#define REG_RX_ADDR_P4 0x0E
#define REG_RX_ADDR_P5 0x0F
#define REG_TX_ADDR    0x10
#define REG_RX_PW_P0   0x11
#define REG_RX_PW_P1   0x12
#define REG_RX_PW_P2   0x13
#define REG_RX_PW_P3   0x14
#define REG_RX_PW_P4   0x15
#define REG_RX_PW_P5   0x16
#define REG_FIFO_STATUS 0x17
#define REG_DYNPD      0x1C
#define REG_FEATURE    0x1D

#define VAL_RF_SETUP_250K 0x26
#define VAL_RF_SETUP_1M   0x06
#define VAL_RF_SETUP_2M   0x0E

#define VAL_SETUP_AW_3B 1
#define VAL_SETUP_AW_4B 2
#define VAL_SETUP_AW_5B 3

#define RADIO_PACKET_LEN  32

typedef struct _radioPacket
{
  unsigned char raw[RADIO_PACKET_LEN];
} radioPacket;

/* nRF24L SPI commands */
#define CMD_R_REG              0x00
#define CMD_W_REG              0x20
#define CMD_R_RX_PAYLOAD       0x61
#define CMD_W_TX_PAYLOAD       0xA0
#define CMD_FLUSH_TX           0xE1
#define CMD_FLUSH_RX           0xE2
#define CMD_REUSE_TX_PL        0xE3
#define CMD_ACTIVATE           0x50
#define CMD_RX_PL_WID          0x60
#define CMD_W_ACK_PAYLOAD(P)  (0xA8|(P&0x0F))
#define CMD_W_PAYLOAD_NO_ACK   0xD0
#define CMD_NOP                0xFF

/* Usefull macro */
#define RADIO_EN_CS() GPIO_ResetBits(RADIO_GPIO_CS_PORT, RADIO_GPIO_CS)
#define RADIO_DIS_CS() GPIO_SetBits(RADIO_GPIO_CS_PORT, RADIO_GPIO_CS)
#define RADIO_DIS_CE() GPIO_ResetBits(RADIO_GPIO_CE_PORT, RADIO_GPIO_CE)
#define RADIO_EN_CE() GPIO_SetBits(RADIO_GPIO_CE_PORT, RADIO_GPIO_CE)
#define ACTIVATE_DATA   0x73

#define RADIO_CONNECTED_TIMEOUT   (2000)


/* Synchronisation */
xSemaphoreHandle dataRdy;
/* Data queue */
xQueueHandle rxQueue;
xQueueHandle txQueue;


static uint32_t lastPacketTick;
/* Private variables */
static bool nrfisInit;

/***********************
 * SPI private methods *
 ***********************/
static char spiSendByte(char byte)
{
  /* Loop while DR register in not emplty */
  while (SPI_I2S_GetFlagStatus(RADIO_SPI, SPI_I2S_FLAG_TXE) == RESET);

  /* Send byte through the SPI1 peripheral */
  SPI_I2S_SendData(RADIO_SPI, byte);

  /* Wait to receive a byte */
  while (SPI_I2S_GetFlagStatus(RADIO_SPI, SPI_I2S_FLAG_RXNE) == RESET);

  /* Return the byte read from the SPI bus */
  return SPI_I2S_ReceiveData(RADIO_SPI);
}

static char spiReceiveByte()
{
  return spiSendByte(DUMMY_BYTE);
}

/****************************************************************
 * nRF SPI commands, Every commands return the status byte      *
 ****************************************************************/

/* Read len bytes from a nRF24L register. 5 Bytes max */
unsigned char nrfReadReg(unsigned char address, char *buffer, int len)
{
  unsigned char status;
  int i;

  RADIO_EN_CS();
  /* Send the read command with the address */
  status = spiSendByte( CMD_R_REG | (address&0x1F) );
  /* Read LEN bytes */
  for(i=0; i<len; i++)
    buffer[i]=spiReceiveByte();

  RADIO_DIS_CS();
  return status;
}

/* Write len bytes a nRF24L register. 5 Bytes max */
unsigned char nrfWriteReg(unsigned char address, char *buffer, int len)
{
  unsigned char status;
  int i;

  RADIO_EN_CS();
  /* Send the write command with the address */
  status = spiSendByte( CMD_W_REG | (address&0x1F) );
  /* Write LEN bytes */
  for(i=0; i<len; i++)
    spiSendByte(buffer[i]);

  RADIO_DIS_CS();
  return status;
}

/* Write only one byte (useful for most of the reg.) */
unsigned char nrfWrite1Reg(unsigned char address, char byte)
{
  return nrfWriteReg(address, &byte, 1);
}

/* Read only one byte (useful for most of the reg.) */
unsigned char nrfRead1Reg(unsigned char address) {

  char byte;
  nrfReadReg(address, &byte, 1);
  return byte;
}

/* Sent the NOP command. Used to get the status byte */
unsigned char nrfNop()
{
  unsigned char status;

  RADIO_EN_CS();
  status = spiSendByte(CMD_NOP);
  RADIO_DIS_CS();

  return status;
}

unsigned char nrfFlushRx()
{
  unsigned char status;

  RADIO_EN_CS();
  status = spiSendByte(CMD_FLUSH_RX);
  RADIO_DIS_CS();

  return status;
}

unsigned char nrfFlushTx()
{
  unsigned char status;

  RADIO_EN_CS();
  status = spiSendByte(CMD_FLUSH_TX);
  RADIO_DIS_CS();

  return status;
}

// Return the payload length
unsigned char nrfRxLength(unsigned int pipe)
{
  unsigned char length;

  RADIO_EN_CS();
  spiSendByte(CMD_RX_PL_WID);
  length = spiReceiveByte();
  RADIO_DIS_CS();

  return length;
}

unsigned char nrfActivate()
{
  unsigned char status;
  
  RADIO_EN_CS();
  status = spiSendByte(CMD_ACTIVATE);
  spiSendByte(ACTIVATE_DATA);
  RADIO_DIS_CS();

  return status;
}

// Write the ack payload of the pipe 0
unsigned char nrfWriteAck(unsigned int pipe, char *buffer, int len)
{
  unsigned char status;
  int i;

//  ASSERT(pipe<6);

  RADIO_EN_CS();

  /* Send the read command with the address */
  status = spiSendByte(CMD_W_ACK_PAYLOAD(pipe));
  /* Read LEN bytes */
  for(i=0; i<len; i++)
    spiSendByte(buffer[i]);

  RADIO_DIS_CS();

  return status;
}

// Read the RX payload
unsigned char nrfReadRX(unsigned char *buffer, int len)
{
  unsigned char status;
  int i;

  RADIO_EN_CS();

  /* Send the read command with the address */
  status = spiSendByte(CMD_R_RX_PAYLOAD);
  /* Read LEN bytes */
  for(i=0; i<len; i++)
    buffer[i]=spiReceiveByte();

  RADIO_DIS_CS();
  return status;
}


void nrfSetChannel(unsigned int channel)
{
  if (channel<126)
    nrfWrite1Reg(REG_RF_CH, channel);
}

void nrfSetDatarate(int datarate)
{
  switch(datarate)
  {
    case RADIO_RATE_250K:
      nrfWrite1Reg(REG_RF_SETUP, VAL_RF_SETUP_250K);
      break;
    case RADIO_RATE_1M:
      nrfWrite1Reg(REG_RF_SETUP, VAL_RF_SETUP_1M);
      break;
    case RADIO_RATE_2M:
      nrfWrite1Reg(REG_RF_SETUP, VAL_RF_SETUP_2M);
      break;
  }  
}

void nrfSetAddress(unsigned int pipe, char* address)
{
  int len = 5;

//  ASSERT(pipe<6);

  if (pipe > 1)
    len = 1;
  
  nrfWriteReg(REG_TX_ADDR,           address, len);
  nrfWriteReg(REG_RX_ADDR_P0 + pipe, address, len);
}

void nrfSetEnable(bool enable)
{
  if (enable)
  {
    RADIO_EN_CE();
  } 
  else
  {
    RADIO_DIS_CE();
  }
}

unsigned char nrfGetStatus()
{
  return nrfNop();
}

bool nrfInterruptActive(void)
{
  return (GPIO_ReadInputDataBit(RADIO_GPIO_IRQ_PORT, RADIO_GPIO_IRQ) == Bit_RESET);
}


/* Initialisation */
void nrfInit(void)
{
  GPIO_InitTypeDef GPIO_InitStructure;
  SPI_InitTypeDef  SPI_InitStructure;
  EXTI_InitTypeDef EXTI_InitStructure;
  NVIC_InitTypeDef NVIC_InitStructure;

  /* Enable GPIO & SPI clocks */
  RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
  RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
  RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO,  ENABLE);
  RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1,  ENABLE);

  GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable,ENABLE);//release 3 port
  /* Configure SPI pins: SCK, MOSI, MISO */
  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_SPI_SCK 
            | RADIO_GPIO_SPI_MOSI |  RADIO_GPIO_SPI_MISO;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
  GPIO_Init(RADIO_GPIO_SPI_PORT, &GPIO_InitStructure);

  /* Configure I/O for the Chip Select & Chip Enable*/
  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_CS;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
  GPIO_Init(RADIO_GPIO_CS_PORT, &GPIO_InitStructure);
  
  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_CE;
  GPIO_Init(RADIO_GPIO_CE_PORT, &GPIO_InitStructure);

  /* Configure the interruption (EXTI Source) */

  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_IRQ;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
  GPIO_Init(RADIO_GPIO_IRQ_PORT, &GPIO_InitStructure);

  /* SPI configuration */
  SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
  SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
  SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
  SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
  SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
  SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
  SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
  SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
  SPI_InitStructure.SPI_CRCPolynomial = 7;
  SPI_Init(RADIO_SPI, &SPI_InitStructure);

  /* Enable the SPI  */
  SPI_Cmd(RADIO_SPI, ENABLE);
  
  /* Enable the EXTI interrupt router */
  GPIO_EXTILineConfig(RADIO_GPIO_IRQ_SRC_PORT, RADIO_GPIO_IRQ_SRC);
  EXTI_InitStructure.EXTI_Line = RADIO_GPIO_IRQ_LINE;
  EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
  EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
  EXTI_InitStructure.EXTI_LineCmd = ENABLE;
  EXTI_Init(&EXTI_InitStructure);

  NVIC_InitStructure.NVIC_IRQChannel = EXTI4_IRQn;
  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_RADIO_PRI;
  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
  NVIC_Init(&NVIC_InitStructure);
  
  /* disable the chip select */
  RADIO_DIS_CS();
  /* disable the chip enable */
  RADIO_DIS_CE();

}

void nrfInterruptHandler(void)
{
  
  portBASE_TYPE  xHigherPriorityTaskWoken = pdFALSE;

  if(EXTI_GetITStatus(RADIO_GPIO_IRQ_LINE) != RESET)
  {
    //To unlock RadioTask
    xSemaphoreGiveFromISR(dataRdy, &xHigherPriorityTaskWoken);
    if(xHigherPriorityTaskWoken)
      portYIELD();
    EXTI_ClearITPendingBit(RADIO_GPIO_IRQ_LINE);
  }

}


/***********************public functions**********************/

static void nrfConfigure(void)
{
  int i;
  char radioAddress[5] = {0xE1, 0xE2, 0xE3, 0xE4, 0xE5};

  //Set radio address
  nrfSetAddress(0, radioAddress);
  
  nrfSetChannel(40);
  nrfSetDatarate(2);  //Set the radio data rate 2M

  nrfWrite1Reg(REG_EN_RXADDR,1);//Enable Pipe 0
  nrfWrite1Reg(REG_EN_AA,1);    //Enable Auto Ack: Pipe0
  nrfWrite1Reg(REG_RX_PW_P0,0x20);
  nrfWrite1Reg(REG_SETUP_AW,3);

  //Power the radio, Enable the DS interruption, set the radio in PRX mode
  nrfWrite1Reg(REG_CONFIG, 0x0F);
  
  nrfWriteReg(REG_TX_ADDR,radioAddress,5);
  nrfWrite1Reg(REG_SETUP_RETR,0x1a);
  nrfWrite1Reg(REG_STATUS,0xfe);

  // Enable the dynamic payload size and the ack payload for the pipe 0
  nrfWrite1Reg(REG_FEATURE, 0x06);
  nrfWrite1Reg(REG_DYNPD, 0x01);

  //Flush RX
  for(i=0;i<3;i++)
    nrfFlushRx();
  //Flush TX
  for(i=0;i<3;i++)
    nrfFlushTx();
}

u8 Nrf24l01_Check(void)
{ 
  char buf1[5]={0};
  char radioAddress[5] = {0xE1, 0xE2, 0xE3, 0xE4, 0xE5};
  u8 i; 
  
  nrfWriteReg(0x30,radioAddress,5); 
  nrfReadReg(REG_TX_ADDR,buf1,5); 
  for(i=0;i<5;i++) 
  { 
    if(buf1[i]!=radioAddress[i]) 
      break; 
  } 
  if(i==5)
    return SUCCESS ;
  else
    return ERROR ;
}

/*
 * Public functions
 */

//time after last SPI IRQ
bool isConnected(void)
{
  if ((xTaskGetTickCount() - lastPacketTick) > RADIO_CONNECTED_TIMEOUT)
    return false;

  return true;
}

void radioTest(void)
{
  
  if( Nrf24l01_Check() == SUCCESS){
    printf("Nrf24l01 Check returns SUCCESS\r\n");
  }else{
    printf("Nrf24l01 Check returns ERROR\r\n");
  }
}

/* Radio task handles the packet transfers */
static void radiolinkTask(void * arg)
{
  unsigned char dataLen;
  radioPacket pk;

  //Packets handling loop
  while(1)
  {

    xSemaphoreTake(dataRdy, portMAX_DELAY);
    lastPacketTick = xTaskGetTickCount();

    nrfSetEnable(false);
    
    //Fetch all the data (Loop until the RX Fifo is NOT empty)
    while( !(nrfRead1Reg(REG_FIFO_STATUS)&0x01) )
    {
      dataLen = nrfRxLength(0);

      if (dataLen>RADIO_PACKET_LEN)          //If a packet has a wrong size it is dropped
        nrfFlushRx();
      else                     //Else, it is processed
      {
        nrfReadRX(pk.raw, dataLen);
        xQueueSend( rxQueue, &pk, 0);
      }
    }

    //Push the data to send (Loop until the TX Fifo is full or there is no more data to send)
    while( (uxQueueMessagesWaiting((xQueueHandle)txQueue) > 0) && !(nrfRead1Reg(REG_FIFO_STATUS)&0x20) )
    {
      xQueueReceive(txQueue, &pk, 0);
      nrfWriteAck(0, (char*) pk.raw, RADIO_PACKET_LEN);
    }

    //clear the interruptions flags
    nrfWrite1Reg(REG_STATUS, 0x70);
    //Re-enable the radio
    nrfSetEnable(true);
  }
}

void radiolinkInit(void)
{
  if(nrfisInit)
    return;

  nrfInit();
  radioTest();
  nrfConfigure();

  /* Initialise the semaphores */
  vSemaphoreCreateBinary(dataRdy);

  /* Queue init */
  rxQueue = xQueueCreate(3, RADIO_PACKET_LEN);
  txQueue = xQueueCreate(3, RADIO_PACKET_LEN);

  /* Launch the Radio link task */
  xTaskCreate(radiolinkTask, "radiolinkTask",
              configMINIMAL_STACK_SIZE, NULL, 4, NULL);

  printf("radiolinkTask created over\r\n" );
  nrfisInit = true;
}

int sendPacket(unsigned char * pk)
{
  xQueueSend(txQueue, pk, portMAX_DELAY);
  return 0;
}

int receivePacket(unsigned char * pk)
{
  xQueueReceive( rxQueue, pk, portMAX_DELAY);
  return 0;
}

void radioTestTask(void *param)
{
  
  unsigned char buff[RADIO_PACKET_LEN] = "";
  printf("This is in radioTestTask\r\n");
  
  while(1)  
  {
    receivePacket(buff);
    printf("radio received: %s \r\n",buff);
  }
}

 



菜鸟
2015-07-16 15:40:06     打赏
15楼
楼主牛人

菜鸟
2015-11-07 23:42:22     打赏
16楼

赞一个,发现第一个用操作系统的


助工
2017-11-03 08:38:00     打赏
17楼

学习学习


共17条 2/2 1 2 跳转至

回复

匿名不能发帖!请先 [ 登陆 注册 ]