STM32F407(CubeMX+HAL+USB(vcp))移植rosserial和ROS通信

前言

之前尝试过移植好rosserial的stm32通过串口和ROS系统建立通信,但无奈在类似于发布IMU类似的数据量很大的消息或消息的发布频率较高时经常会出现一些问题(发布频率达不到设定要求,启动rosserial的终端会报一些警告和错误),在一般的学习中还可以,但在实际的应用中基本达不到使用要求。
写道这想说明一点:我对整个rosserial内部的通信机制也不是很了解,类似于通信速度达到多少可以满足通信速度的需求,如何测试通信速度等等问题(我也很纳闷为什么串口就会存在这些问题),如果大家有什么见解欢迎交流。

一、基于STM32CubeMX建立STM32F407USB虚拟串口基本工程

  1. 配置STM32F407单片机的时钟源,时钟源选择为晶振
    配置时钟源
  2. 配置调试方式和时基,此处选择的为SW模式。时基选择为系统滴答定时器。
    配置调试方式和时基3. 配置USB为全速模式下的仅设备模式
    配置USB模式
  3. 这里使用ST官方提供的USB设备库,并使用CDC类
    配置USB设备模式
  4. 配置系统时钟,这里晶振频率为8M并将系统时钟配置为最高的168M,并注意USB的时钟为48M
    配置时钟频率
  5. 这里要特别注意一点,下面红框中标示的,堆空间一定要改大,否则会在设备管理器中显示黄色的感叹号。
    配置工程属性
  6. 这些都配置完之后便可以点击右上角的生成代码按钮,来生成基本工程代码。
    配置工程属性

二、根据基本工程修改USB部分的代码,提供rosserial会用到的串口收发接口。

这一部分推荐看一篇帖子:http://bbs.21ic.com/icview-811704-1-1.html
这里主要修改usbd_cdc_if.c文件,首先我们要明确其中两个函数的功能。

static int8_t CDC_Receive_FS(uint8_t* Buf, uint32_t *Len)
{
  /* USER CODE BEGIN 6 */
  USBD_CDC_SetRxBuffer(&hUsbDeviceFS, &Buf[0]);
  USBD_CDC_ReceivePacket(&hUsbDeviceFS);
  return (USBD_OK);
  /* USER CODE END 6 */
}

uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len)
{
  uint8_t result = USBD_OK;
  /* USER CODE BEGIN 7 */
  USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)hUsbDeviceFS.pClassData;
  if (hcdc->TxState != 0){
    return USBD_BUSY;
  }
  USBD_CDC_SetTxBuffer(&hUsbDeviceFS, Buf, Len);
  result = USBD_CDC_TransmitPacket(&hUsbDeviceFS);
  /* USER CODE END 7 */
  return result;
}

单从这两个函数的名字上看也比较好理解,上面的时数据接收函数,下面的时数据发送函数。CDC_Receive_FS(uint8_t* Buf, uint32_t *Len)是数据接收的回调函数,USB每次收到数据后都会调用该函数将接收到的数据存入Buf指向的缓冲区当中,Len是接收到数据的长度。USBD_CDC_ReceivePacket()函数的作用是复位OUT端点接收缓冲区,CDC_Itf_Receive()函数在接收完数据之后要调用该函数复位缓冲区。因此如果接收到的数据没有及时处理,就会被下次接收到的数据覆盖掉了。所以在此处要增加数据转存环节。

#define USB_RX_DATA_SIZE 2048

uint8_t usb_rxBuffer[USB_RX_DATA_SIZE];
uint32_t usb_rxBufPtrIn = 0;
uint32_t usb_rxBufPtrOut = 0;

static int8_t CDC_Receive_FS(uint8_t* Buf, uint32_t *Len)
{
  /* USER CODE BEGIN 6 */
  uint32_t i;
  uint16_t in;
  for(i = 0; i < *Len; ++i)
  {
    in = (usb_rxBufPtrIn + 1) % USB_RX_DATA_SIZE;
    if(in != usb_rxBufPtrOut) //USB接收缓冲区未满
    {
      usb_rxBuffer[usb_rxBufPtrIn] = Buf[i];
      usb_rxBufPtrIn = in;
    }
  }
  
  USBD_CDC_SetRxBuffer(&hUsbDeviceFS, &Buf[0]);
  USBD_CDC_ReceivePacket(&hUsbDeviceFS);
  return (USBD_OK);
  /* USER CODE END 6 */
}

这样处理最终实现的效果是将接收到的数据存入了一环形缓冲区。再将数据存好之后便可以为rosserial提供接口函数了

//接收缓冲区中的数据大小
int vcp_available(void)
{
  return ((uint32_t)(USB_RX_DATA_SIZE + usb_rxBufPtrIn - usb_rxBufPtrOut)) % USB_RX_DATA_SIZE;
}
//从接收缓冲区中读取
int vcp_read(void)
{
  // if the head isn't ahead of the tail, we don't have any characters
  if(usb_rxBufPtrIn == usb_rxBufPtrOut)
  {
    return -1;
  }
  else
  {
    unsigned char ch = usb_rxBuffer[usb_rxBufPtrOut];
    usb_rxBufPtrOut = (uint16_t)(usb_rxBufPtrOut + 1) % USB_RX_DATA_SIZE;
    return ch;
  }
}
//通过usb_vcp向外发送
void vcp_write(uint8_t* Buf, uint16_t Len)
{
  while(CDC_Transmit_FS(Buf, Len) != HAL_OK);
}

三、将ros_lib增加到工程中,并修改STM32Hardware.h文件

ros_lib 可以根据rosserial wiki 的教程中执行产生。
ros_lib增加到工程中之后会报找不到round函数的错误,和一系列警告消息。
在这里插入图片描述
针对找不到round()函数的错误可以在增加__USE_C99_MATH的宏,针对大量警告的问题可以在Misc Controls 的位置增加如:–diag_suppress=num,(num,为警告信息#号后面的数字)。
接下来的重点便是修改STM32Hardware.h文件了。
这里试了一下不能直接粘贴太多代码,就介绍一下如何修改好了。
在开头的地方增加:

extern __IO uint32_t uwTick;

将类内部的读写函数修改为:

int read(){
     if(vcp_available()){
    return vcp_read();
     }else{
     return -1;
     } 
     void write(uint8_t* data, int length){
     vcp_write(data, length);
    }

将时间函数改为

unsigned long time(){return uwTick;}

到此整个移植工作便结束了,接下来可以按照rosserial wiki上面的教程开始测试学习了。

发布了48 篇原创文章 · 获赞 78 · 访问量 6万+

猜你喜欢

转载自blog.csdn.net/xiaoyuanwuhui/article/details/97895473