查看: 1218|回复: 0

[分享] MCX N947:移植Micro-ROS

[复制链接]

该用户从未签到

712

主题

6371

帖子

0

超级版主

Rank: 8Rank: 8

积分
24974
最后登录
2025-7-25
发表于 2024-11-11 17:37:29 | 显示全部楼层 |阅读模式
本帖最后由 小恩GG 于 2024-11-11 17:37 编辑

1. 概述MCXN947芯片是一款高度集成的微控制器,具有强大的处理能力、丰富的外设支持和高级安全特性,适用于多种复杂应用。
NXP FRDM-MCXN947板是一款基于MCXN947设备的低成本设计与评估板。NXP为MCXN947设备提供了包括硬件评估板、软件开发集成开发环境(IDE)、示例应用程序和驱动程序在内的工具和软件支持。
Micro-ROS是ROS 2的嵌入式版本,‌专门设计用于在嵌入式系统中运行,‌以支持机器人和嵌入式设备的实时控制和通信。‌ 它将ROS 2的强大功能扩展到资源受限的嵌入式平台,‌如微控制器和嵌入式系统。‌Micro-ROS的出现使得嵌入式系统和机器人应用能够更紧密地与ROS 2生态系统集成,‌从而实现更高级别的机器人自动化和控制。‌
2-1.png
在本文中,我们将探讨如何在MCXN947板移植Micro-ROS。
硬件环境:
  • 开发板:FRDM-MCXN947

软件环境:
  • Ubuntu 22.04
  • IDE:MCUXpresso IDE v11.9.0
  • SDK:SDK Builder | MCUXpresso SDK Builder (nxp.com)

2. ROS2 架构
在深入探讨MicroROS的移植过程之前,让我们先对全新的ROS2架构进行简要介绍。这是因为MicroROS在其设计和实现中大量借鉴了ROS2的抽象层源码。ROS2与它的前身ROS1在核心通信机制上有着显著的不同。最突出的变化是ROS2采用了DDS(数据分发服务)作为其通信和节点发现的协议,而ROS1则依赖于XML-RPC协议,并且需要在主节点启动后其他节点才能加入。
ROS1对于嵌入式设备的支持受限主要是因为XML-RPC机制在这些环境下需要引入大量的软件包依赖。为了解决这个问题,像rosserial这样的项目为MCU和PC上的主节点之间的通信定制了更轻量级的通信协议。相比之下,ROS2引入了工业界成熟的DDS协议,该协议已经在军工、航天和金融系统领域证明了自己的稳定性。
值得一提的是,DDS只是一个标准协议,不同的公司可能会有不同的实现,例如Cyclone DDS(由Eclipse提供)、Fast DDS和Micro XRCE-DDS(两者都是由eProsima提供)。为了确保在使用不同厂商的DDS实现时上层的ROS2代码不需要变动,ROS2定义了一系列的抽象层接口,如RCL(ROS客户端库)和RMW(ROS中间件)。
这些底层的DDS实现都提供了一致的RMW接口。在RMW之上,则是C语言实现的RCL,这允许它进一步向上提供对不同编程语言的支持,包括C++、Python和Java等。因此,要想成功移植ROS2到一个实时操作系统(RTOS),关键在于该RTOS需要支持一个具体的DDS实现及其对应的RMW接口。只有这样,上层的RCL和ROS应用程序代码才能够无需任何修改地运行。
现在我们了解到,ROS2主要由RCL(ROS客户端库)、RMW(ROS中间件接口)以及DDS(数据分发服务)组成。要将ROS2移植到新的平台或系统上,核心工作便在于实现一套兼容的RMW和DDS组合,而上层的RCL则可以保持原样,无需修改。在这个框架下,MicroROS正是提供了这样的RMW和DDS组合。
具体来说,MicroROS采用的DDS是专门为嵌入式设备设计的Micro XRCE DDS(针对极端资源受限环境的DDS标准),并且配有与之适配的RMW实现。这使得MicroROS不仅兼容ROS2的架构,还能有效地运行在资源有限的嵌入式设备上。
因此,移植MicroROS到不同的硬件平台,本质上就是需要将其通信协议如UART(通用异步收发传输器)和UDP(用户数据报协议)与MicroROS的RMW+DDS组合进行对接。这一过程涉及确保MicroROS能够通过这些通信协议与平台上的其他节点或外部系统有效交互,同时保持其轻量级和高效性,以适应嵌入式设备的特殊需求。


2-2.png
通过上述介绍,我们可以看出MicroROS 的移植主要有 2 个部分:
对接 UART / UDP 通信和时钟,也就是实现 default_transport.cpp 里面的 5 个函数。打包 DDS + RMW + RCL 生成 libmicroros.a 静态库。

3. Micro-ROS静态库工具链和环境配置
3.1 工具链配置
首先在Ubuntu 22.04 LTS上安装ROS 2。并运行如下命令。
  1. sudo apt update&&sudo apt install locales
  2. sudo locale-gen en_US en_US.UTF-8
  3. sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
  4. export LANG=en_US.UTF-8
  5. sudo apt update && sudo apt install curl gnupg lsb-release
  6. sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
复制代码

(1)sudo apt update: 使用管理员权限(sudo)更新系统软件包列表,确保获取最新的软件包信息。
(2)sudo apt install locales: 使用管理员权限安装locales软件包,它提供了管理和配置本地化的工具。
(3)sudo locale-gen en_US en_US.UTF-8: 使用管理员权限生成英文(美国)的本地化环境,包括en_US和en_US.UTF-8。
(4)sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8: 使用管理员权限更新系统的本地化设置,将LC_ALL和LANG环境变量设置为en_US.UTF-8,即英语(美国)的UTF-8编码。
(5)export LANG=en_US.UTF-8: 将当前用户的LANG环境变量设置为en_US.UTF-8,以便在终端中使用英语(美国)的UTF-8编码显示文本。
(6)sudo apt update && sudo apt install curl gnupg lsb-release: 使用管理员权限更新系统软件包列表,并安装curl、gnupg和lsb-release软件包。这些软件包分别用于在终端中执行网络请求、处理GPG加密和获取发行版信息。
(7)sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg: 使用管理员权限从GitHub仓库下载ROS的公钥文件(ros.key),并将其保存到系统的密钥环目录(/usr/share/keyrings/)下,命名为ros-archive-keyring.gpg。这个公钥用于验证ROS软件包的完整性和来源。
3.2 Ubuntu 安装ROS
配置和构建Micro-ROS的开发环境的。运行如下命令。
  1. sudo apt update && sudo apt upgrade && sudo apt install ros-humble-desktop
  2. source /opt/ros/humble/setup.bash && echo “source /opt/ros/humble/setup.bash” >>~/.bashrc
  3. source /opt/ros/$ROS_DISTRO/setup.bash
  4. mkdir uros_ws && cd uros_ws
  5. git clone -b iron https://github.com/micro-ROS/micro_ros_setup.git src/micro_ros_setup
  6. rosdep update && rosdep install --from-paths src --ignore-src -y
  7. colcon build
  8. source install/local_setup.bash
  9. ros2 run micro_ros_setup create_firmware_ws.sh generate_lib
复制代码


(1) 更新软件和安装ROS(Robot Operating System)
(2) 设置和保存ROS环境的配置。
(3) 这两个命令创建一个新的目录uros_ws(工作空间),然后切换到该目录。
(4) 从GitHub仓库克隆名为micro_ros_setup的项目,并将其放在工作空间的src目录下。
(5) 这两个命令用于安装项目所需的依赖项。如果运行此命令报错,请参考附录2。
(6) 这个命令使用colcon构建系统来编译和安装项目。Colcon是一个通用的构建工具,适用于多种编程语言和平台。如果运行此命令报错,请参考附录3。
(7) create_firmware_ws.sh: 这是要运行的可执行文件的名称。它可能是一个用于创建固件工作空间(firmware workspace)的脚本。这条命令的目的是运行micro_ros_setup包中的create_firmware_ws.sh脚本,并传递参数generate_lib来生成一个包含Micro-ROS库的固件工作空间。这一步需要从github下载大量的源码。失败后下次生成会提示firmware已经存在,要rm这个文件夹。如果出现以下图片,证明代码下载成功。
2-3.png
4. Micro-ROS静态库生成
如果工具链和环境配置成功,回到工作空间下,现在我们应该有五个文件夹
分别为build、 fireware、 install、 log、 src。
2-4.png
其中fireware是我们生成micro-ros的空间
cd fireware
4.1 根据目标处理器配置toolchain.cmake文件
进入fireware目录中,这里面的colcon.meta和toolchain.cmake就是我们生成静态库需要指定的配置文件了,其中colcon.meta描述了我们micro-ros的配置,toolchain.cmake描述了单片机的平台。
我们可以打开MCUXpresso查找MCXN947相关配置。并创建toolchain.cmake。

  1. set(CMAKE_SYSTEM_NAME Generic)
  2. set(CMAKE_CROSSCOMPILING 1)
  3. set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY)

  4. # SET HERE THE PATH TO YOUR C99 AND C++ COMPILERS
  5. # 在这里添加编译器路径
  6. set(PIX /opt/gcc-arm-none-eabi-10.3-2021.10/bin)
  7. set(CMAKE_C_COMPILER ${PIX}/arm-none-eabi-gcc)
  8. set(CMAKE_CXX_COMPILER ${PIX}/arm-none-eabi-g++)

  9. set(CMAKE_C_COMPILER_WORKS 1 CACHE INTERNAL "")
  10. set(CMAKE_CXX_COMPILER_WORKS 1 CACHE INTERNAL "")

  11. # SET HERE YOUR BUILDING FLAGS
  12. set(FLAGS "-O2 -ffunction-sections -fdata-sections -fno-exceptions -mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard -nostdlib -mthumb --param max-inline-insns-single=500 -D'RCUTILS_LOG_MIN_SEVERITY=RCUTILS_LOG_MIN_SEVERITY_NONE'" CACHE STRING "" FORCE)
  13. #-mcpu=cortex-m3 改成 -mcpu=cortex-m33
  14. #  加入 mfpu=fpv5-d16 -mfloat-abi=hard 支持硬件浮点编译
  15. set(CMAKE_C_FLAGS_INIT "-std=c11 ${FLAGS} -DCLOCK_MONOTONIC=0 -D'__attribute__(x)='" CACHE STRING "" FORCE)
  16. set(CMAKE_CXX_FLAGS_INIT "-std=c++11 ${FLAGS} -fno-rtti -DCLOCK_MONOTONIC=0 -D'__attribute__(x)='" CACHE STRING "" FORCE)

  17. set(__BIG_ENDIAN__ 0)
复制代码


上面就是cmake的写法。
其中,"-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard":这些选项指定了目标处理器的架构和浮点单元特性。
我们可以查看MCXN947的目标处理器的架构和浮点单元特性。

2-5.png
我们可以打开MCUXpresso,打开一个MCXN947工程,在settings->MCU Linker 中的All options 中查看mcpu=cortex-m33 -mfpu=fpv5-sp-d16 mfloat-abi=hard。
所以MCXN947系列的是M33内核,我们需要将-mcpu=cortex-m7 修改成 -mcpu=cortex-m33,其他基本不需要改动。从这块我们也可以看出来,生产的静态库一个系列应该都是通用的!

4.2 根据Micro-ROS需求配置colcon.meta文件
  1. touch colcon.meta

  2. {
  3.     "names": {
  4.         "tracetools": {
  5.             "cmake-args": [
  6.                 "-DTRACETOOLS_DISABLED=ON",
  7.                 "-DTRACETOOLS_STATUS_CHECKING_TOOL=OFF"
  8.             ]
  9.         },
  10.         "rosidl_typesupport": {
  11.             "cmake-args": [
  12.                 "-DROSIDL_TYPESUPPORT_SINGLE_TYPESUPPORT=ON"
  13.             ]
  14.         },
  15.         "rcl": {
  16.             "cmake-args": [
  17.                 "-DBUILD_TESTING=OFF",
  18.                 "-DRCL_COMMAND_LINE_ENABLED=OFF",
  19.                 "-DRCL_LOGGING_ENABLED=OFF"
  20.             ]
  21.         },
  22.         "rcutils": {
  23.             "cmake-args": [
  24.                 "-DENABLE_TESTING=OFF",
  25.                 "-DRCUTILS_NO_FILESYSTEM=ON",
  26.                 "-DRCUTILS_NO_THREAD_SUPPORT=ON",
  27.                 "-DRCUTILS_NO_64_ATOMIC=ON",
  28.                 "-DRCUTILS_AVOID_DYNAMIC_ALLOCATION=ON"
  29.             ]
  30.         },
  31.         "microxrcedds_client": {
  32.             "cmake-args": [
  33.                 "-DUCLIENT_PIC=OFF",
  34.                 "-DUCLIENT_PROFILE_UDP=OFF",
  35.                 "-DUCLIENT_PROFILE_TCP=OFF",
  36.                 "-DUCLIENT_PROFILE_DISCOVERY=OFF",
  37.                 "-DUCLIENT_PROFILE_SERIAL=OFF",
  38.                 "-UCLIENT_PROFILE_STREAM_FRAMING=ON",
  39.                 "-DUCLIENT_PROFILE_CUSTOM_TRANSPORT=ON",
  40.                 "-DUCLIENT_PROFILE_SHARED_MEMORY=ON",   #允许内存共享
  41.                 "-DUCLIENT_SHARED_MEMORY_MAX_ENTITIES=20"
  42.             ]
  43.         },
  44.         "rmw_microxrcedds": {
  45.             "cmake-args": [
  46.                 "-DRMW_UXRCE_MAX_NODES=5",  #最大节点数
  47.                 "-DRMW_UXRCE_MAX_PUBLISHERS=6", #最大发布者数量
  48.                 "-DRMW_UXRCE_MAX_SUBSCRIPTIONS=4",        #最大订阅者数量
  49.                 "-DRMW_UXRCE_MAX_SERVICES=6",                #最大服务端数量
  50.                 "-DRMW_UXRCE_MAX_CLIENTS=1",                #最大客户端数量
  51.                 "-DRMW_UXRCE_MAX_HISTORY=4",               
  52.                 "-DRMW_UXRCE_TRANSPORT=custom"                #自定义传输接口
  53.             ]
  54.         }
  55.     }
  56. }
复制代码


4.3 生成Micro-ROS静态库
运行如下两条命令生产静态库。
  1. source install/local_setup.bash

  2. ros2 run micro_ros_setup build_firmware.sh $(pwd)/firmware/toolchain.cmake $(pwd)/firmware/colcon.meta
复制代码
如果成功生成会静态库,你会在firmware/build文件中看到libmicroros.a
2-6.png
5. 整合本地工程并测试
5.1 将生成的静态库加入本地工程
2-7.png
2-8.png
Folder name 起名为 bsp_include。

将include 所有文件夹加入工程中。
2-9.png
将include文件中所有路径加入includepath中。
将生成好的libmicroros.a静态库加入工程中,例如加入bsp_include中。
2-10.png

将libmicrorots.a静态库和名字路径加入Libraries(-l)和Library search path(-L).
加入静态库和相关头文件后,可以编译。
5.2 实现串口通信接口函数
为了将Micro-ROS移植到MCU,我们必须提供传输层的功能,通过通信接口进行读写的功能。可以在Micro-ROS GitHub中找到的其他示例实现,来自一些预制插件和端口。在这里,我将展示每个所需传输函数的示例代码。
  1. rmw_ret_t rmw_uros_set_custom_transport(

  2.   bool framing,

  3.   void * args,

  4.   open_custom_func open_cb,

  5.   close_custom_func close_cb,

  6.   write_custom_func write_cb,

  7.   read_custom_func read_cb);
复制代码

通过该结构体,可以看出通信接口函数组主要包含open,close,write,read。
open:此函数负责初始化(打开)传输层使用的外围设备。如果外围设备在其他地方初始化,并且在调用Micro-ROS函数之前,此函数为空。
close:此功能负责取消初始化(关闭)传输层使用的外围设备。因为不需要取消初始化函数。此函数也为空。
write:此函数负责在外围设备上写入数据(字节)。要写入的字节数和字节本身分别作为参数“len”和“buf”给出。
read:此功能负责从外围设备读取数据(字节)。要读取的字节数在函数参数“len”中指定,字节应通过函数参数“buf”返回。
写入数据和读取数据通过
  1. bool transport_close(struct uxrCustomTransport * transport) {



  2.         return true;

  3. }

  4. bool transport_open(struct uxrCustomTransport * transport) {



  5.         return true;

  6. }

  7. size_t transport_write(struct uxrCustomTransport* transport, const uint8_t * buf, size_t len, uint8_t * err) {

  8.         FLEXIO_UART_WriteBlocking(&uartDev, buf, len);

  9.         return sizeof(len);

  10. }

  11. size_t transport_read(struct uxrCustomTransport* transport, uint8_t* buf, size_t len, int timeout, uint8_t* err) {

  12.         Serial.setTimeout(timeout);

  13.         FLEXIO_UART_ReadBlocking(&uartDev, buf, len);

  14.         return sizeof(len);

  15. }
复制代码


此外,还需要一个返回系统时基的函数。这个时基不一定是实时的,也就是正确的世界时间,它可以是自启动以来的时间或类似的时间,
此函数不必传递给Micro-ROS,只需使用如上所示的正确名称和参数创建即可。

  1. int clock_gettime(void) {

  2.         IRTC_GetDatetime(RTC, &datetimeGet);

  3.         return 0;

  4. }
复制代码


5.3 测试
使Micro-ROS实际运行。这由两部分组成:在MCU上运行的客户端和在主机PC上运行的代理。
基本微ROS客户端(MCU)
从客户端开始,创建和运行Micro-ROS客户端所需的最小步骤(和代码)如下。这些说明基于创建节点的Micro-ROS文档。
下面是实现前面所有步骤的代码,创建和启动Micro-ROS客户端:

  1. //Required global variables

  2. rcl_allocator_t allocator;

  3. rclc_support_t support;

  4. rcl_node_t node;

  5. rclc_executor_t executor;



  6. rmw_ret_t error;



  7. //Set Communication functions

  8. rmw_uros_set_custom_transport(

  9.         true,

  10.         NULL,

  11.         rtt_transport_open,

  12.         rtt_transport_close,

  13.         rtt_transport_write,

  14.         rtt_transport_read

  15. );



  16. //Set Allocation functions (Optional)

  17. rcl_allocator_t allocator = rcutils_get_zero_initialized_allocator();

  18. allocator.allocate = rtt_allocate;

  19. allocator.deallocate = rtt_deallocate;

  20. allocator.reallocate = rtt_reallocate;

  21. allocator.zero_allocate = rtt_zero_allocate;

  22. (void)!rcutils_set_default_allocator(&allocator);



  23. //Get allocator

  24. allocator = rcl_get_default_allocator();



  25. //Create init_options

  26. error = rclc_support_init(&support, 0, NULL, &allocator);



  27. //Create node

  28. error = rclc_node_init_default(&node, "uROS_Terminal", "", &support);



  29. //Create executor

  30. error = rclc_executor_init(&executor, &support.context, 1, &allocator);



  31. //Call the executor periodically e.g. in the while(1) loop or a thread:

  32. while(1) {

  33.         error = rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));

  34. }
复制代码


基本Micro-ROS设置的另一部分是代理,它在主机PC上运行。代理在MCU上运行的Micro-ROS和主机PC上的ROS 2之间建立接口,它是Micro-ROS(和DDS)代理。代理通过定义的自定义接口连接到MCU上运行的Micro-ROS。对于这个代理,不需要编写代码,只需要构建代理,就像任何其他ROS 2包一样,并且以与构建Micro-ROS静态库类似的方式构建。此处显示的说明基于Micro-ROS文档,用于创建代理。

  1. # Go to the Micro-ROS workspace folder

  2. cd microros_ws



  3. # Source ROS 2

  4. source /opt/ros/humble/setup.bash



  5. # Source local packages

  6. source install/local_setup.bash



  7. # Create Agent

  8. ros2 run micro_ros_setup create_agent_ws.sh



  9. # Build Agent

  10. ros2 run micro_ros_setup build_agent.sh



  11. # Possible ROS Update

  12. sudo rosdep init

  13. rosdep update
复制代码



成功构建Micro-ROS代理后,以下bash命令启动/运行代理:
  1. # Go to the Micro-ROS workspace folder

  2. cd microros_ws



  3. # Source ROS 2

  4. source /opt/ros/humble/setup.bash



  5. # Source local packages

  6. source install/local_setup.bash



  7. # Run Agent (serial connection)

  8. ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0 -b 921600 -v6
复制代码


在这些bash命令中,最后一个是实际启动Micro-ROS代理的命令。它需要几个参数,第一个是要使用的连接类型,这里是串行连接。然后是两个仅适用于串行连接的参数:“–dev/ttyUSB0”,用于设置要使用的串行接口(要列出linux中的所有串行接口,可以使用以下bash命令:“dmesg | grep tty”),以及“-b 921600”,用于设置串行接口波特率(此处为921600)。

使用Micro-ROS Agent进行测试和运行
启动Micro-ROS代理后,MCU可以通过串行接口连接到主机PC,并重置以建立新的连接。如果以下Micro-ROS代理终端输出:
2-11.png
证明移植成功。






回复

使用道具 举报

您需要登录后才可以回帖 注册/登录

本版积分规则

关闭

站长推荐上一条 /3 下一条

Archiver|手机版|小黑屋|恩智浦技术社区

GMT+8, 2025-7-29 09:49 , Processed in 0.081641 second(s), 20 queries , MemCache On.

Powered by Discuz! X3.4

Copyright © 2001-2024, Tencent Cloud.

快速回复 返回顶部 返回列表