基于VCP虚拟串口的Rosserial接口教程

2 篇文章 6 订阅

Rosserial的用法这篇文章中,我们介绍了如何在stm32中通过串口添加ROS的功能和接口,这篇文章接着上篇,介绍如何通过VCP虚拟串口来提升Rosserial的性能。

通过cube添加VCP驱动

首先按网上教程用cube在项目中添加VCP虚拟串口,具体步骤就不详述了,到处都能找到,这里要强调的是,USB FS模式下必须设置48Mhz的时钟。

修改VCP驱动

我们需要修改usbd_cdc_if.c 和usbd_cdc_if.h文件
打开usbd_cdc_if.c ,首先修改CDC_Receive_FS()回调函数,代码如下:

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

其实只添加了WirteRingbuffer(&usb_vcp_ringbuf,Buf,*Len);这一行,usb_vcp_ringbuf是一个环形缓冲区,我们将usb串口接收到的数据暂存到里面。
接下来在usbd_cdc_if.c 中,还是添加三个函数,分别是Vcp_Read、Vcp_Write和Vcp_Available,代码如下:

uint32_t Vcp_Available(void) {
  return GetRingbufferValidLen(&usb_vcp_ringbuf);
}
//从接收缓冲区中读取
uint8_t Vcp_Read(void) {
  uint8_t ch = 0;
  taskENTER_CRITICAL();
  ReadRingbuffer(&usb_vcp_ringbuf,&ch,1);
  taskEXIT_CRITICAL();
  return ch;
}
//通过usb_vcp向外发送
void Vcp_Write(uint8_t *Buf, uint16_t Len) {
  while (CDC_Transmit_FS(Buf, Len) != HAL_OK) {
    osDelay(1);
  };
}

代码也很简单,这里主要强调两点:

  1. VCP接收回调函数CDC_Receive_FS是中断里面执行的,也就是说,对环形缓冲区usb_vcp_ringbuf进行写操作是在中断中完成的,而Vcp_Read中,对环形缓冲区进行读操作是在任务里面完成的,因此最好对读环形缓冲区加一个保护,最简单的方式就是加一个临界区,当然也可以用信号量来实现
  2. Vcp_Write通过VCP发送数据时,由于有个等待发送ok的过程,最好在等待的循环中加一个osDelay(1),以便留给操作系统更多调度时间

最后我们在usbd_cdc_if.h中添加上述三个函数的声明

 /* USER CODE BEGIN EXPORTED_FUNCTIONS */
void Vcp_Write(uint8_t* Buf, uint16_t Len);
uint8_t Vcp_Read(void);
uint32_t Vcp_Available(void);
/* USER CODE END EXPORTED_FUNCTIONS */

修改Rosserial接口

同样的,进入STM32Hardware.h文件,分别实现三个函数:int read()、 void write(uint8_t *data, int length)及unsigned long time()就可以了

class STM32Hardware {
protected:
public:
  STM32Hardware() {}
  void init() {}
  int read() {
    if (Vcp_Available()) {
      return Vcp_Read();
    } else {
      return -1;
    }
  }
  void flush(void) {}
  void write(uint8_t *data, int length) { Vcp_Write(data, length); }
  unsigned long time() { return HAL_GetTick(); }

protected:
};

其它说明

  1. 改为VCP后,将stm32通过虚拟串口接入上位机,串口识别的名字可能会有变化,默认可能会变成/dev/ttyACM0,另外,使用serial_node.py连接stm32时,波特率的设置是没有意义的,实际传输是按照USB的速度执行。传输速度比普通串口还是要快得多的。
  2. 按默认配置实际使用中,如果通过rosserial收发的消息较多,有可能会收到错误提示:
    Message from device dropped: message larger than buffer.
    这是由于Node Handle中默认定义的输入输出缓冲大小太小造成,我们打开项目的ros.h文件,找到下面的代码。
namespace ros
{
  typedef NodeHandle_<STM32Hardware, 25, 25, 512, 512> NodeHandle; // default 25, 25, 512, 512
}

这个模板NodeHandle_的定义在ros/node_handle.h里

/* Node Handle */
template<class Hardware,
         int MAX_SUBSCRIBERS = 25,
         int MAX_PUBLISHERS = 25,
         int INPUT_SIZE = 512,
         int OUTPUT_SIZE = 512>

可以看到这四个数分别表示最大的订阅消息数、最大发送消息数、输入和输出缓冲大小。我们把后面两个数改大即可,在ros.h中修改NodeHandle的声明,根据自己芯片的可用内存大小适当改大两个缓冲区即可。比如我改成了1024

namespace ros
{
  typedef NodeHandle_<STM32Hardware, 25, 25, 1024, 1024> NodeHandle; // default 25, 25, 512, 512
}

除此之外,VCP本身还有个缓冲区大小,在usbd_cdc_if.h中,有两个宏定义,分别是APP_RX_DATA_SIZE和APP_TX_DATA_SIZE ,如果stm32内存比较充裕,这个也可以尽量大点,我一般设为2048

#define APP_RX_DATA_SIZE  2048
#define APP_TX_DATA_SIZE  2048
  • 2
    点赞
  • 9
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值