基于STM32H743与FreeRTOS的micro-ROS环境搭建

本文分享在STM32开发板上搭建micro-ROS环境(以STM32H743为例)。

开发环境是linux下的vscode + arm-none-eabi-toolchain + openocd + STM32CubeMX。

参考内容如下:

micro-ROS 官方git仓库:https://github.com/micro-ROS

视频:【搬】如何在任何 STM32 微控制器上设置 micro-ROS_哔哩哔哩_bilibili

git仓库:https://github.com/lFatality/stm32_micro_ros_setup

blog:Run Micro-ROS on almost any stm32 - Tech blog

一、目标

在STM32微控制器上构建ROS2节点并通过UART通讯将消息传输到运行ROS2的PC上。

二、步骤

micro-ROS:

1)根据自己的STM32MCU型号在STM32CubeMX中创建工程项目

串口+DMA配置:

STM32与PC基于UART+DMA进行通讯,串口参数配置如下,USARTx_RX DMA配置为Circular模式、优先级均设为Very High,并打开串口全局中断。

FreeRTOS任务配置:

采用CMSIS_V2接口,FreeRTOS任务堆栈分配20000 bytes,默认任务堆栈大小应大于10000bytes,设置为12000bytes,配置hal库时基为TIM1,时钟频率按需配置,项目管理中设置工具链为Makefile,之后生成项目文件。

2)生成Micro-ROS静态库

在CubeMX生成的项目目录下克隆micro-ROS仓库:

git clone https://github.com/micro-ROS/micro_ros_stm32cubemx_utils.git

在CubeMX生成的Makefile文件里加入以下内容(插入位置参考图片):

#######################################
# micro-ROS addons
#######################################
LDFLAGS += micro_ros_stm32cubemx_utils/microros_static_library/libmicroros/libmicroros.a
C_INCLUDES += -Imicro_ros_stm32cubemx_utils/microros_static_library/libmicroros/microros_include

# Add micro-ROS utils
C_SOURCES += micro_ros_stm32cubemx_utils/extra_sources/custom_memory_manager.c
C_SOURCES += micro_ros_stm32cubemx_utils/extra_sources/microros_allocators.c
C_SOURCES += micro_ros_stm32cubemx_utils/extra_sources/microros_time.c

# Set here the custom transport implementation
C_SOURCES += micro_ros_stm32cubemx_utils/extra_sources/microros_transports/dma_transport.c

print_cflags:
	@echo $(CFLAGS)

使用docker下载官方提供的镜像并运行生成静态库(笔者使用的ROS2版本是humble,如有必要请修改代码里的ROS版本):

docker pull microros/micro_ros_static_library_builder:humble
docker run -it --rm -v $(pwd):/project --env MICROROS_LIBRARY_FOLDER=micro_ros_stm32cubemx_utils/microros_static_library microros/micro_ros_static_library_builder:humble

注意这里可能会报各种错误,笔者遇到的主要是网络问题,目前没找到很好的解决办法,建议多试几次。若成功的话静态库文件所在路径:

.../micro_ros_stm32cubemx_utils/microros_static_library/libmicroros/libmicroros.a

进入Core/Src/freertos.c文件加入以下内容:

#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <uxr/client/transport.h>
#include <rmw_microxrcedds_c/config.h>
#include <rmw_microros/rmw_microros.h>

#include <std_msgs/msg/int32.h>

#include "usart.h"
bool cubemx_transport_open(struct uxrCustomTransport * transport);
bool cubemx_transport_close(struct uxrCustomTransport * transport);
size_t cubemx_transport_write(struct uxrCustomTransport* transport, const 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);

void * microros_allocate(size_t size, void * state);
void microros_deallocate(void * pointer, void * state);
void * microros_reallocate(void * pointer, size_t size, void * state);
void * microros_zero_allocate(size_t number_of_elements, size_t size_of_element, void * state);
void StartDefaultTask(void *argument)
{
    /* USER CODE BEGIN StartDefaultTask */
    /* Infinite loop */
    // micro-ROS configuration

    rmw_uros_set_custom_transport(
      true,
      (void *) &huart2,
      cubemx_transport_open,
      cubemx_transport_close,
      cubemx_transport_write,
      cubemx_transport_read);

    rcl_allocator_t freeRTOS_allocator = rcutils_get_zero_initialized_allocator();
    freeRTOS_allocator.allocate = microros_allocate;
    freeRTOS_allocator.deallocate = microros_deallocate;
    freeRTOS_allocator.reallocate = microros_reallocate;
    freeRTOS_allocator.zero_allocate =  microros_zero_allocate;

    if (!rcutils_set_default_allocator(&freeRTOS_allocator)) {
        printf("Error on default allocators (line %d)\n", __LINE__);
    }

    // micro-ROS app

    rcl_publisher_t publisher;
    std_msgs__msg__Int32 msg;
    rclc_support_t support;
    rcl_allocator_t allocator;
    rcl_node_t node;

    allocator = rcl_get_default_allocator();

    //create init_options
    rclc_support_init(&support, 0, NULL, &allocator);

    // create node
    rclc_node_init_default(&node, "cubemx_node", "", &support);

    // create publisher
    rclc_publisher_init_default(
      &publisher,
      &node,
      ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
      "cubemx_publisher");

    msg.data = 0;

    for(;;)
    {
      rcl_ret_t ret = rcl_publish(&publisher, &msg, NULL);
      if (ret != RCL_RET_OK)
      {
        printf("Error publishing (line %d)\n", __LINE__);
      }

      msg.data++;
      osDelay(10);
    }
    /* USER CODE END StartDefaultTask */
}

3)在自己的IDE环境中编译与烧录程序

若编译报错显示缺少undefined reference to _kill 或者 undefined reference to _getpid,原因是缺少syscalls.c文件,可以尝试在Src文件夹下加入以下文件:

/**
 ******************************************************************************
 * @file      syscalls.c
 * @author    Auto-generated by STM32CubeIDE
 * @brief     STM32CubeIDE Minimal System calls file
 *
 *            For more information about which c-functions
 *            need which of these lowlevel functions
 *            please consult the Newlib libc-manual
 ******************************************************************************
 * @attention
 *
 * Copyright (c) 2020-2023 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.
 *
 ******************************************************************************
 */

/* Includes */
#include <sys/stat.h>
#include <stdlib.h>
#include <errno.h>
#include <stdio.h>
#include <signal.h>
#include <time.h>
#include <sys/time.h>
#include <sys/times.h>


/* Variables */
extern int __io_putchar(int ch) __attribute__((weak));
extern int __io_getchar(void) __attribute__((weak));


char *__env[1] = { 0 };
char **environ = __env;


/* Functions */
void initialise_monitor_handles()
{
}

int _getpid(void)
{
  return 1;
}

int _kill(int pid, int sig)
{
  (void)pid;
  (void)sig;
  errno = EINVAL;
  return -1;
}

void _exit (int status)
{
  _kill(status, -1);
  while (1) {}    /* Make sure we hang here */
}

__attribute__((weak)) int _read(int file, char *ptr, int len)
{
  (void)file;
  int DataIdx;

  for (DataIdx = 0; DataIdx < len; DataIdx++)
  {
    *ptr++ = __io_getchar();
  }

  return len;
}

__attribute__((weak)) int _write(int file, char *ptr, int len)
{
  (void)file;
  int DataIdx;

  for (DataIdx = 0; DataIdx < len; DataIdx++)
  {
    __io_putchar(*ptr++);
  }
  return len;
}

int _close(int file)
{
  (void)file;
  return -1;
}


int _fstat(int file, struct stat *st)
{
  (void)file;
  st->st_mode = S_IFCHR;
  return 0;
}

int _isatty(int file)
{
  (void)file;
  return 1;
}

int _lseek(int file, int ptr, int dir)
{
  (void)file;
  (void)ptr;
  (void)dir;
  return 0;
}

int _open(char *path, int flags, ...)
{
  (void)path;
  (void)flags;
  /* Pretend like we always fail */
  return -1;
}

int _wait(int *status)
{
  (void)status;
  errno = ECHILD;
  return -1;
}

int _unlink(char *name)
{
  (void)name;
  errno = ENOENT;
  return -1;
}

int _times(struct tms *buf)
{
  (void)buf;
  return -1;
}

int _stat(char *file, struct stat *st)
{
  (void)file;
  st->st_mode = S_IFCHR;
  return 0;
}

int _link(char *old, char *new)
{
  (void)old;
  (void)new;
  errno = EMLINK;
  return -1;
}

int _fork(void)
{
  errno = EAGAIN;
  return -1;
}

int _execve(char *name, char **argv, char **env)
{
  (void)name;
  (void)argv;
  (void)env;
  errno = ENOMEM;
  return -1;
}

micro-ROS agent:

接下来创建micro-ROS代理,负责在STM32与ROS2之间建立通信。

1)新建文件夹克隆micro_ros_setup库

git clone -b $ROS_DISTRO https://github.com/micro-ROS/micro_ros_setup.git src/micro_ros_setup
rosdepc update && rosdepc install --from-path src --ignore-src -y
colcon build
source install/local_setup.bash

2)构建micro_ros_setup软件包

ros2 run micro_ros_setup create_agent_ws.sh
ros2 run micro_ros_setup build_agent.sh
source install/local_setup.sh

3)启动micro-ros-agent

ros2 run micro_ros_agent micro_ros_agent serial -b 115200 --dev /dev/ttyUSB0

4)在代理中,应该可以看见以下内容

[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)

5)运行publisher收到stm32发送的节点消息

ros2 topic echo /cubemx_publisher
---
data: 2399
---
data: 2400
---
data: 2401
---
data: 2402
---
data: 2403
---
data: 2404
---

笔者水平有限,以上若有不正确的地方,欢迎大家批评指正。 

  • 22
    点赞
  • 27
    收藏
    觉得还不错? 一键收藏
  • 1
    评论
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值