ROS - rosserial从入门到入坟

我直接以搭建在jeston nano的Ubunu18(ROS-melodic)为例,使用ros搭建rosserial的开发环境,并通过rosserial和VCP虚拟端口来连接stm32f407开发板。

配套视频教程:【rosserial库用于stm32与ROS通信-哔哩哔哩】

一、ros安装环境

  ubuntu18使用的ros版本为melodic,对应下载相应版本的ros,这里参考Ubuntu18.04安装Ros(最新最详细亲测)-优快云博客的手动下载安装ros。

  此处略过安装ubuntu18的过程,ubuntu18的官方镜像地址为:Ubuntu 18.04.6 LTS (Bionic Beaver)

  a.安装ROS

sudo sh -c '. /etc/lsb-release && echo "deb http://mirrors.ustc.edu.cn/ros/ubuntu/ `lsb_release -cs` main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
sudo apt update
sudo apt install ros-melodic-desktop-full  
#注:这里以及后面所有的安装ros包都需要根据版本安装,不一定是melodic
echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc
source ~/.bashrc

    ros安装完成之后需要下载rosdep依赖安装工具,由于国内网络被墙,这里的安装方法如下:

  b.安装rosdep

    rosdep是依赖安装工具,当ros包中存在缺失的依赖时,rosdep可以方便的补全ros包依赖,在update过程中可能会超时,添加raw.githubusercontent.com网站的ipv4在/etc/hosts文件中即可

sudo apt-get install python3-rosdep 
sudo apt-get install python-rosdep python-rosinstall python-wstool build-essential
sudo rosdep init
rosdep update

    这一步也可以使用社区版本代替,尤其是网络问题严重时,更加建议使用社区版

sudo apt install -y python3-pip
sudo pip3 install rosdepc
sudo rosdepc init
rosdepc update

  c.ros安装完成后即可开始创建ros工作空间,在桌面上新建ros文件夹,用作于ros工作空间

cd /Desktop/
mkdir -p ros/src
cd ros
catkin_make
rosdepc install --from-paths src --ignore-src -r -y

二、rosserial搭建

  a.先来到ros工作空间下的src目录,克隆rosserial,并编译rosserial功能包

cd src
git clone https://github.com/yoneken/rosserial_stm32.git
catkin_make
source devel/setup.sh

cd src git clone https://github.com/yoneken/rosserial_stm32.git catkin_make source devel/setup.sh

  b.安装好rosserial功能包后,需要使用rosserial构建用于stm32通信的头文件包(库)

sudo apt-get install ros-melodic-rosserial
sudo apt-get install ros-melodic-rosserial-arduino
cd ~ //到工作空间根目录下
sudo chmod 777 -R /home/robot/.ros
mkdir -p stm32_roslib/Inc
cd stm32_roslib
rosrun rosserial_stm32 make_libraries.py ./

    顺利完成以上步骤后,你可以通过rosserial功能包获得用于stm32的库,cope这个你生成的stm32_roslib库到你的stm32项目文件夹下,以完成后面的工作。(b这个步骤你可以省略,使用我提供的build好的库,在文末你可以看到,我已经上传到了gitee仓库上了)

三、stm32搭建

  你可以在装有ubuntu18的系统上安装stm32CudeIDE用于stm32的环境开发,也可以在其他电脑上完成,只需要cope上文中的stm32_roslib库到stm32CubeIDE或者CubeMX项目文件夹下即可。我以安装在我电脑上的CubeIDE为例,搭建stm32项目(强烈建议使用Stm32CubeIDE,防止因混编导致编译问题)。

  概述:本案例使用stm32的rtos构建整个stm32的系统框架,主要是做复杂的多任务处理,另外使用了stm32的USB功能,实现了一个VCP虚拟端口,用于与上位机ros通信,网上有教程是使用usart,当然相比于usart,VCP更快也更稳定。

  CubeIDE配置如下:

1.RCC外部晶振,高速和低速都打开 
2.Connectivity内打开USB_OTG_FS,配置为Device_Only模式,打开NVIC中断 
3.配置时钟图,确保USB_FS的时钟为48M 
4.配置USB_VCP虚拟端口 
5.配置FreeRTOS,并设置用于ROS通信的任务大小为静态同时至少为3000 
6.Project Manager配置LinkerSettings最小Heap Size为0X800(其实我也不知道有什么作用,但是有的博客确实提到要设置)

  注:使用CubeIDE在创建项目时需要使用C++创建,在CubeMX则需要在MDK里头设置

  这里的框架配置较多,不明白注意看我给的视频连接。

四、rosserial初体验

  1.对stm32HAL库文件的更改和stm32_roslib文件的更改

    由于我们使用USB_VCP来实现ROS通信,我们除了要导入build好的stm32_roslib库,还需要对库里的文件做一定的更改,具体如下(折叠内容):(这个库我已经修改并上传到了gitee上,详看文末,你可以跳过某些步骤)

    文件STM32Hardware.h(直接换成我这个)

    这个文件位于我们build好的stm32_roslib文件中,是ros库与stm32库的一个接口,主要改动在于把原有的usart接口换成vcp接口

  #ifndef ROS_STM32_HARDWARE_H_
  #define ROS_STM32_HARDWARE_H_

  #define STM32F4xx  // Change for your device
  #define USB

  #ifdef STM32F3xx
  #include "stm32f3xx_hal.h"
  //#include "stm32f3xx_hal_uart.h"
  #endif /* STM32F3xx */
  #ifdef STM32F4xx
  #include "stm32f4xx_hal.h"
  //#include "stm32f4xx_hal_uart.h"
  #endif /* STM32F4xx */
  #ifdef STM32F7xx
  #include "stm32f7xx_hal.h"
  //#include "stm32f7xx_hal_uart.h"
  #endif /* STM32F7xx */

  #ifdef USB

  // Change "CDC_Transmit_FS" and "CDC_Receive_FS" Function
  // in '../USB_DEVICE/App/usbd_cdc_if.c'
  #include "usbd_cdc_if.h"
  #include "usb_device.h"

  extern uint8_t UserRxBufferFS[APP_RX_DATA_SIZE];
  extern uint32_t rx_head;   // From usbd_cdc_if.h

  class STM32Hardware {
   private:
          uint32_t rx_tail;

   public:
    STM32Hardware(){}

    // Any initialization code necessary to use the serial port:
    void init() {
            rx_head = rx_tail = 0u;
    }

    // Read a byte from the serial port. -1 = failure:
    int read() {
            // Quit if no new character:
            if (rx_head == rx_tail){
                    memset(UserRxBufferFS, 0, sizeof(UserRxBufferFS));
                    rx_head = rx_tail = 0u;
                    return -1;
            }
            // Get next char in buffer:
            return static_cast<int>(UserRxBufferFS[rx_tail++]);
    }

    // Write data to the connection to ROS:
    void write(uint8_t* data, int length) {
            while(CDC_Transmit_FS((uint8_t *)data, length) != USBD_OK);//确保发完再发
    }

    // Returns milliseconds since start of program:
    unsigned long time() { return HAL_GetTick(); };
  };

  #endif /* USB */
  #endif

  文件usbd_cdc_if.c(注意更改这个HAL库的文件)

    这个文件在USB_DEVICE/App下,属于stm32HAL库的文件,注意改动

/* USER CODE BEGIN Header */
/**
  ******************************************************************************
  * @file           : usbd_cdc_if.c
  * @version        : v1.0_Cube
  * @brief          : Usb device for Virtual Com Port.
  ******************************************************************************
  * @attention
  *
  * Copyright (c) 2024 STMicroelectronics.
  * All rights reserved.
  *
  * This software is licensed under terms that can be found in the LICENSE file
  * in the root directory of this software component.
  * If no LICENSE file comes with this software, it is provided AS-IS.
  *
  ******************************************************************************
  */
/* USER CODE END Header */

/* Includes ------------------------------------------------------------------*/
#include "usbd_cdc_if.h"

/* USER CODE BEGIN INCLUDE */
#include "string.h"
#include "stdarg.h"
#include "stdio.h"
/* USER CODE END INCLUDE */

/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/

/* USER CODE BEGIN PV */
/* Private variables ---------------------------------------------------------*/

/* USER CODE END PV */

/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
  * @brief Usb device library.
  * @{
  */

/** @addtogroup USBD_CDC_IF
  * @{
  */

/** @defgroup USBD_CDC_IF_Private_TypesDefinitions USBD_CDC_IF_Private_TypesDefinitions
  * @brief Private types.
  * @{
  */

/* USER CODE BEGIN PRIVATE_TYPES */

/* USER CODE END PRIVATE_TYPES */

/**
  * @}
  */

/** @defgroup USBD_CDC_IF_Private_Defines USBD_CDC_IF_Private_Defines
  * @brief Private defines.
  * @{
  */

/* USER CODE BEGIN PRIVATE_DEFINES */
/* USER CODE END PRIVATE_DEFINES */

/**
  * @}
  */

/** @defgroup USBD_CDC_IF_Private_Macros USBD_CDC_IF_Private_Macros
  * @brief Private macros.
  * @{
  */

/* USER CODE BEGIN PRIVATE_MACRO */

/* USER CODE END PRIVATE_MACRO */

/**
  * @}
  */

/** @defgroup USBD_CDC_IF_Private_Variables USBD_CDC_IF_Private_Variables
  * @brief Private variables.
  * @{
  */
/* Create buffer for reception and transmission           */
/* It's up to user to redefine and/or remove those define */
/** Received data over USB are stored in this buffer      */
uint8_t UserRxBufferFS[APP_RX_DATA_SIZE];

/** Data to send over USB CDC are stored in this buffer   */
uint8_t UserTxBufferFS[APP_TX_DATA_SIZE];

/* USER CODE BEGIN PRIVATE_VARIABLES */
uint32_t rx_head = 0;
uint32_t tx_head = 0;

/* USER CODE END PRIVATE_VARIABLES */

/**
  * @}
  */

/** @defgroup USBD_CDC_IF_Exported_Variables USBD_CDC_IF_Exported_Variables
  * @brief Public variables.
  * @{
  */

extern USBD_HandleTypeDef hUsbDeviceFS;

/* USER CODE BEGIN EXPORTED_VARIABLES */

/* USER CODE END EXPORTED_VARIABLES */

/**
  * @}
  */

/** @defgroup USBD_CDC_IF_Private_FunctionPrototypes USBD_CDC_IF_Private_FunctionPrototypes
  * @brief Private functions declaration.
  * @{
  */

static int8_t CDC_Init_FS(void);
static int8_t CDC_DeInit_FS(void);
static int8_t CDC_Control_FS(uint8_t cmd, uint8_t* pbuf, uint16_t length);
static int8_t CDC_Receive_FS(uint8_t* pbuf, uint32_t *Len);
static int8_t CDC_TransmitCplt_FS(uint8_t *pbuf, uint32_t *Len, uint8_t epnum);

/* USER CODE BEGIN PRIVATE_FUNCTIONS_DECLARATION */

/* USER CODE END PRIVATE_FUNCTIONS_DECLARATION */

/**
  * @}
  */

USBD_CDC_ItfTypeDef USBD_Interface_fops_FS =
{
  CDC_Init_FS,
  CDC_DeInit_FS,
  CDC_Control_FS,
  CDC_Receive_FS,
  CDC_TransmitCplt_FS
};

/* Private functions ---------------------------------------------------------*/
/**
  * @brief  Initializes the CDC media low layer over the FS USB IP
  * @retval USBD_OK if all operations are OK else USBD_FAIL
  */
static int8_t CDC_Init_FS(void)
{
  /* USER CODE BEGIN 3 */
  /* Set Application Buffers */
  USBD_CDC_SetTxBuffer(&hUsbDeviceFS, UserTxBufferFS, 0);
  USBD_CDC_SetRxBuffer(&hUsbDeviceFS, UserRxBufferFS);
  return (USBD_OK);
  /* USER CODE END 3 */
}

/**
  * @brief  DeInitializes the CDC media low layer
  * @retval USBD_OK if all operations are OK else USBD_FAIL
  */
static int8_t CDC_DeInit_FS(void)
{
  /* USER CODE BEGIN 4 */
  return (USBD_OK);
  /* USER CODE END 4 */
}

/**
  * @brief  Manage the CDC class requests
  * @param  cmd: Command code
  * @param  pbuf: Buffer containing command data (request parameters)
  * @param  length: Number of data to be sent (in bytes)
  * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
  */
static int8_t CDC_Control_FS(uint8_t cmd, uint8_t* pbuf, uint16_t length)
{
  /* USER CODE BEGIN 5 */
  switch(cmd)
  {
    case CDC_SEND_ENCAPSULATED_COMMAND:

    break;

    case CDC_GET_ENCAPSULATED_RESPONSE:

    break;

    case CDC_SET_COMM_FEATURE:

    break;

    case CDC_GET_COMM_FEATURE:

    break;

    case CDC_CLEAR_COMM_FEATURE:

    break;

  /*******************************************************************************/
  /* Line Coding Structure                                                       */
  /*-----------------------------------------------------------------------------*/
  /* Offset | Field       | Size | Value  | Description                          */
  /* 0      | dwDTERate   |   4  | Number |Data terminal rate, in bits per second*/
  /* 4      | bCharFormat |   1  | Number | Stop bits                            */
  /*                                        0 - 1 Stop bit                       */
  /*                                        1 - 1.5 Stop bits                    */
  /*                                        2 - 2 Stop bits                      */
  /* 5      | bParityType |  1   | Number | Parity                               */
  /*                                        0 - None                             */
  /*                                        1 - Odd                              */
  /*                                        2 - Even                             */
  /*                                        3 - Mark                             */
  /*                                        4 - Space                            */
  /* 6      | bDataBits  |   1   | Number Data bits (5, 6, 7, 8 or 16).          */
  /*******************************************************************************/
    case CDC_SET_LINE_CODING:

    break;

    case CDC_GET_LINE_CODING:

    break;

    case CDC_SET_CONTROL_LINE_STATE:

    break;

    case CDC_SEND_BREAK:

    break;

  default:
    break;
  }

  return (USBD_OK);
  /* USER CODE END 5 */
}

/**
  * @brief  Data received over USB OUT endpoint are sent over CDC interface
  *         through this function.
  *
  *         @note
  *         This function will issue a NAK packet on any OUT packet received on
  *         USB endpoint until exiting this function. If you exit this function
  *         before transfer is complete on CDC interface (ie. using DMA controller)
  *         it will result in receiving more data while previous ones are still
  *         not sent.
  *
  * @param  Buf: Buffer of data to be received
  * @param  Len: Number of data received (in bytes)
  * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
  */
static int8_t CDC_Receive_FS(uint8_t* Buf, uint32_t *Len)
{
  /* USER CODE BEGIN 6 */
          rx_head += *Len;
          USBD_CDC_SetRxBuffer(&hUsbDeviceFS, &Buf[0]);
          USBD_CDC_ReceivePacket(&hUsbDeviceFS);
          return (USBD_OK);
  /* USER CODE END 6 */
}

/**
  * @brief  CDC_Transmit_FS
  *         Data to send over USB IN endpoint are sent over CDC interface
  *         through this function.
  *         @note
  *
  *
  * @param  Buf: Buffer of data to be sent
  * @param  Len: Number of data to be sent (in bytes)
  * @retval USBD_OK if all operations are OK else USBD_FAIL or USBD_BUSY
  */
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;
  tx_head += Len;
  if (hcdc->TxState != 0){
    return USBD_BUSY;
  }

  USBD_CDC_SetTxBuffer(&hUsbDeviceFS, Buf, Len);
  result = USBD_CDC_TransmitPacket(&hUsbDeviceFS);
  tx_head = 0;   // 成功发送包头归位
  /* USER CODE END 7 */
  return result;
}

/**
  * @brief  CDC_TransmitCplt_FS
  *         Data transmitted callback
  *
  *         @note
  *         This function is IN transfer complete callback used to inform user that
  *         the submitted Data is successfully sent over USB.
  *
  * @param  Buf: Buffer of data to be received
  * @param  Len: Number of data received (in bytes)
  * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
  */
static int8_t CDC_TransmitCplt_FS(uint8_t *Buf, uint32_t *Len, uint8_t epnum)
{
  uint8_t result = USBD_OK;
  /* USER CODE BEGIN 13 */
  UNUSED(Buf);
  UNUSED(Len);
  UNUSED(epnum);
  /* USER CODE END 13 */
  return result;
}

/* USER CODE BEGIN PRIVATE_FUNCTIONS_IMPLEMENTATION */

/* USER CODE END PRIVATE_FUNCTIONS_IMPLEMENTATION */

/**
  * @}
  */

/**
  * @}
  */

  2.增加用于ROS通信的文件

    为了让文件结构看着方便和便于移植,我在stm32_roslib/Inc文件夹下添加两个文件为:rosserial_lib.cpp和rosserial_lib.h

    文件rosserial_lib.h,这个文件用于告诉编译器c和c++语言混合编译部分

#ifndef ROSSERIAL_lib__H_
#define ROSSERIAL_lib__H_

#ifdef __cplusplus
 extern "C" {
#endif

void Setup(void);
void Loop(void);

#ifdef __cplusplus
}
#endif
#endif

    文件rosserial_lib.cpp,这个文件是用户自己定义的ros通信文件

#include "rosserial_lib.h"
#include "cmsis_os.h"
#include <ros.h>
#include <std_msgs/String.h>

ros::NodeHandle nh;
std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);

char hello[] = "Hello world!";

void Setup(void) {
    nh.initNode();
    nh.advertise(chatter);
}

void Loop(void) {
    HAL_GPIO_TogglePin(GPIOF, GPIO_PIN_10);
    str_msg.data = hello;
    chatter.publish(&str_msg);
    nh.spinOnce();
    HAL_Delay(500);
}

    除了新增用户文件,还需要在freertos.c文件中调用这些用户配置的函数

    freertos.c文件位于Core/Src,配置部分内容

/* USER CODE BEGIN Includes */
#include "rosserial_lib.h"
/* USER CODE END Includes */

/* USER CODE END Header_StartDefaultTask */
void StartDefaultTask(void *argument)
{
  /* init code for USB_DEVICE */
  MX_USB_DEVICE_Init();
  /* USER CODE BEGIN StartDefaultTask */
  osDelay(500);
  Setup();
  /* Infinite loop */
  osDelay(500);
  for(;;)
  {
   Loop();
  }
  /* USER CODE END StartDefaultTask */
}

五、通信

  将程序烧录到stm32上之后,将stm32的usb_slave接口接到我们的ubuntu电脑上,使用lsusb可以查看挂载到ubuntu的USB设备,可以使用ls /dev/tty*查看接入到ubuntu的所有设备端口(外设会挂在到/dev目录下)

lsusb
ls /dev/tty*

  如果你没有挂载其他非鼠标设备,此时stm32会挂载在/dev/ttyACM0端口上,然后我们就可以启动ROS的agent来使用stm32节点,如下命令,创建一个名为port的命名空间用于stm32serial的agent代理stm32串口节点

 rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0

  如果这一步提示Permission Denied权限不足,使用如下命令给端口权限

sudo chmod 777 -R /dev/ttyACM0

六、结尾

1.rosserial配置和使用示例视频: 【rosserial库用于stm32与ROS通信-哔哩哔哩】

2.stm32_roslib的git仓库,clone到stm32CubeIDE的项目文件夹中:

git clone https://gitee.com/hrilug/stm32_roslib.git

3.补充对于ros_localizition缺失geographiclib库的问题

sudo apt-get install ros-melodic-geographic-*
sudo apt-get install geographiclib-*
sudo apt-get install libgeographic-*

4.参考

在STM32中实现ROS节点——Rosserial的用法-优快云博客

基于VCP虚拟串口的Rosserial接口教程_usbd_vcp 环形-优快云博客

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值