赞
踩
前面的文章已经介绍了如何生成micro-ros的静态库
Micro-ros系列教程(1) 在STM32上部署micro-ros包括自定义消息类型_micro ros静态库编译
但是要想使用到我们的项目中还差了一些步骤,那么今天咱就继续我们的micro-ros教程吧。
比如我们之前没有用到的官方里面的extra_sources
文件夹内的东西。点开我们可以发现有4个文件
第一个文件夹里面包含了一些传输方式,即XRCE-DDS如何与ROS2-Agent通信,比如目前官方提供好的有串口、USB、UDP这三种,如果有想用什么can、spi,自己照猫画虎去写即可(前提是Agent支持这种通信方式)。大家在上一节可能还记得我们在colcon.meta里面写的内容
"rmw_microxrcedds": {
"cmake-args": [
"-DRMW_UXRCE_MAX_NODES=5", #最大节点数
"-DRMW_UXRCE_MAX_PUBLISHERS=6", #最大发布者数量
"-DRMW_UXRCE_MAX_SUBSCRIPTIONS=4", #最大订阅者数量
"-DRMW_UXRCE_MAX_SERVICES=6", #最大服务端数量
"-DRMW_UXRCE_MAX_CLIENTS=1", #最大客户端数量
"-DRMW_UXRCE_MAX_HISTORY=4",
"-DRMW_UXRCE_TRANSPORT=custom" #自定义传输接口
]
}
我们选择的是自定义传输接口,就是说我们要复写底层的接口,其实也就复写四个函数分别是
bool cubemx_transport_open(struct uxrCustomTransport * transport)
bool cubemx_transport_close(struct uxrCustomTransport * transport)
size_t cubemx_transport_write(struct uxrCustomTransport* transport, uint8_t * buf, size_t len, uint8_t * err)
size_t cubemx_transport_read(struct uxrCustomTransport* transport, uint8_t* buf, size_t len, int timeout, uint8_t* err)
打开microros_transports
里面的.c文件可以发现基本都是这样做的,假如官方提供的并不满足你的要求,咱们自己复写一个就行了。
剩下的custom_memory_manager.c
、microros_allocators.c
、microros_time.c
都是根据FreeRTOS的接口帮我们复写好的内存分配、定时器之类的接口,这部分我们可以直接移植到我们项目中,感兴趣可以自己细究。
这一步我们我们以串口DMA的方式为例子详细聊聊我们如何把我们编译好的micro-ros静态库移植到自己的工程中来。
1)根据自己的STM32MCU型号在STM32CubeMX中创建工程项目
串口+DMA配置:
STM32与PC基于UART+DMA进行通讯,串口参数配置如下,USARTx_RX DMA配置为Circular模式、优先级均设为Very High,并打开串口全局中断。
2) FreeRTOS任务配置:
采用CMSIS_V2接口,FreeRTOS任务堆栈分配要尽量给的大一些,在micro-ros初始化的那个任务(通常是默认任务)的堆栈大小应大于10000bytes,这里我们设置为12000bytes,项目管理中设置工具链为Makefile,之后生成项目文件。
然后我们在工程的文件夹里面新建一个_micro-ros_(当然你也可以自己起别的名字),把静态库,头文件和extra_sources文件夹都拷贝到里面来。
在CubeMX生成的Makefile文件里加入以下内容,熟悉Makefile语法的同学应该来说一目了然了:
####################################### # micro-ROS addons ####################################### #添加静态库 LDFLAGS += micro_ros/libmicroros.a #添加头文件路径 C_INCLUDES += -micro_ros/include # Add micro-ROS utils C_SOURCES += micro_ros/extra_sources/custom_memory_manager.c C_SOURCES += micro_ros/extra_sources/microros_allocators.c C_SOURCES += micro_ros/extra_sources/microros_time.c # 包含自定义接口的.c文件,这里我们选择串口DMA通讯 C_SOURCES += micro_ros/extra_sources/microros_transports/dma_transport.c print_cflags: @echo $(CFLAGS)
microros_transports
里面的.c文件并不是所有的都包含进去,而是我们用什么通讯方式就包含哪个,多包含会导致函数重复定义。
当然,有用STMCUBEIDE的同学也可以自己去查找如何包含文件进工程,我在实际项目里面是用cmake去写的,没用过cubeide,这里给出cmake的语法
include_directories( #STM32_H7XX Drivers/STM32H7xx_HAL_Driver/Inc Drivers/BSP/Components/lan8742 Drivers/STM32H7xx_HAL_Driver/Inc/Legacy Drivers/CMSIS/Device/ST/STM32H7xx/Include Drivers/CMSIS/Include Core/Inc #MICRO_ROS micro_ros/include #FREERTOS Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2 Middlewares/Third_Party/FreeRTOS/Source/include Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F ) file(GLOB_RECURSE SOURCES CONFIGURE_DEPENDS "Core/Startup/*.*" "Core/Src/*.c" "Drivers/*.c" "Middlewares/Third_Party/FreeRTOS/*.c" #MICRO_ROS "micro_ros/extra_sources/custom_memory_manager.c" "micro_ros/extra_sources/microros_allocators.c" "micro_ros/extra_sources/microros_time.c" "micro_ros/extra_sources/microros_transports/dma_transport.c" ) add_executable(${PROJECT_NAME}.elf ${SOURCES}) #链接micro_ros库 message(STATUS "link_micro_ros_lib") target_link_libraries(${PROJECT_NAME}.elf ${CMAKE_SOURCE_DIR}/micro_ros/libmicroros.a)
3) 写一个简单的DEMO
这一步大家可以直接参考官网里面的demo文件改写,在此我就不过多赘述,网上案例也多
若编译报错显示缺少undefined reference to _kill 或者 undefined reference to _getpid,原因是缺少syscalls.c文件,这貌似是cubemx在使用Makefile生成时候的一个小bug,我们可以用其他方式生成项目,然后把这个文件复制过来即可。
从下面这张图我们可以看到,嵌入式XRCE-DDS是通过一个Agent功能包接入ROS2网络的,这有点像ros-bridge那味了。
这里推荐鱼香社区的国内版功能包,不得不说小鱼真的为国内开发者方便使用ROS做出了很大的贡献啊!agent 手动编译,不用docker,以及树莓派上使用micros-agent的方法 | 鱼香ROS (fishros.org.cn)
然后运行Agent
ros2 run micro_ros_agent micro_ros_agent serial -b 115200 --dev /dev/ttyUSB0 -v
在代理中,应该可以看见以下内容
[1700054987.933909] info | TermiosAgentLinux.cpp | init | running... | fd: 3
[1700054987.934101] info | Root.cpp | set_verbose_level | logger setup | verbose_level: 4
[1700054992.280208] info | Root.cpp | create_client | create | client_key: 0x5851F42D, session_id: 0x81
[1700054992.280288] info | SessionManager.hpp | establish_session | session established | client_key: 0x5851F42D, address: 0
[1700054992.300421] info | ProxyClient.cpp | create_participant | participant created | client_key: 0x5851F42D, participant_id: 0x000(1)
[1700054992.317128] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x5851F42D, topic_id: 0x000(2), participant_id: 0x000(1)
[1700054992.328021] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x5851F42D, publisher_id: 0x000(3), participant_id: 0x000(1)
[1700054992.340587] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x5851F42D, datawriter_id: 0x000(5), publisher_id: 0x000(3)
监听收到stm32发送的节点消息
ros2 topic echo /cubemx_publisher
---
data: 2399
---
data: 2400
---
data: 2401
---
data: 2402
---
data: 2403
---
data: 2404
---
补充一点:由于我手里用的是H7系列的芯片,直接使用官方给我们的dma_transport.c在开启Cache后是有问题的,毕竟官方这个是针对F4系列写的demo,如果你和我一样是H7系列又开启了Cache,那么自己在dma_transport.c的read函数里面清除一下Cache缓存
本文在上一小节的基础上介绍了我们如何把micros移植到stm32上面,用的是官方自带的小demo做的实验,后面小节我将会陆续介绍micro-ros中话题的发布订阅、服务、参数之类通信方式如何在工程中的应用。
限笔者水平有限,以上若有不正确的地方,欢迎大家批评指正。
如果对您有帮助,麻烦点个star★★★加个关注吧!我会继续努力分享更多ROS2小知识
版权声明:本文为博主原创文章,未经博主允许不得转载。
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。