micro_ros移植到STM32F405RG ,micro_ros STM32裸机

测试日期:2023年11月28日
工具链:STM32CubeIDE++GCC
参考资料:micro_ros_stm32cubemx_utils
注:本文内容仅用于学习参考,不适用于生产环境。
1、准备工作
1.1、安装STM32CubeIDE和STM32CubeMX
1.2、准备mirco_ros 支持cortex-m4的静态库,生成方法可参考我的一篇博文,或者直接下载地址
1.3、下载 micro_ros_stm32cubemx_utils

2、移植过程
2.1、创建STM32CubeMX项目选择芯片为STM32F405RGT6
2.2、工程配置
2.2.1、填写工程名称的路径
2.2.2、Toolchain/IDE配置:STM32CubeIDE

2.3、基本配置
2.3.1、时钟配置,根据开发板配置时钟源为外部8MHZ,系统时钟168M。
2.3.2、开启SW调试功能
2.3.3、调整堆栈大小
在这里插入图片描述
2.4、配置外设
2.4.1、配置USART1 异步模式,波特率921600bps 8N1 用于printf输出
2.4.2、配置USART2 异步模式,波特率115200bps 8N1 使能DMA收发和全局中断 用于mirco_ros 通讯接口
2.4.3、根据开发板配置PD2和PA15为输出,对应LED3和LED2
2.4.4、配置TIM13定时1ms并开启更新中断,用于mirco_ros计时
在这里插入图片描述
2.5、生成代码,并使用CubeIDE打开工程
在这里插入图片描述
2.6、复制文件
2.6.1、复制extra_sources文件夹工作空间
复制micro_ros_stm32cubemx_utils\extra_sources文件夹到CubeIDE工作空间的Core文件夹。我们只使用USART2的DMA传输方式作为mirco_ros接口,因此需要禁用或者删除it_transport.c和usb_cdc_transport.c文件
custom_memory_manager.c文件在freertos上实现了内存分配,因为要改成裸机所以先禁用编译或者直接删除
在这里插入图片描述
extra_sources目录下文件说明:
(1)、microros_transports文件夹:与硬件相关的通讯接口实现,3个C文件分别提供了串口中断、串口DMA和USB虚拟串口传输案列,这里我们只用到串口DMA传输,即dma_transport.c
(2)、custom_memory_manager.c和microros_allocators.c 提供了microros的内寸分配接口实现
(3)、microros_time.c 提供了microros的时间相关接口实现

2.6.2、将静态库文件和头文件复制到工作空间
这里直接把M4lib文件夹直接复制到Core目录,然后禁用编译它们。这一步主要是方便后续引用,不一定要复制进来。
在这里插入图片描述
2.6.3、添加头文件路径
右键项目->Properties->C/C++Build->Setings->MCU GCC Compiler->include paths 点击右边的+图标选择工作空间下的/Core/M4lib/include 文件夹添加头文件路径。
在这里插入图片描述

2.6.4、添加静态库文件和路径
右键项目->Properties->C/C++Build->Setings->MCU GCC linker->Library search path(-L) 点击右边的+图标选择工作空间下的/Core/M4lib 文件夹添加库文件路径,在Libraries(-l) 下添加库文件名microros,注意库文件名在文件夹下为libmicroros.a,GCC连接器-l选项自动添加前面的lib字符和后缀名,因此只需要填写microros
在这里插入图片描述
2.7、修改文件
2.7.1、删除dma_transport.c文件中与freertos相关的无用到代码,然后在DMA接收完成中断回调中重新启动接收,否则程序运行一段时间后打印Error publishing (line xxx)\n。修改后内容如下

#include <uxr/client/transport.h>
#include <rmw_microxrcedds_c/config.h>
#include "main.h"
#include "usart.h"
#include <unistd.h>
#include <stdio.h>
#include <string.h>
#include <stdbool.h>
#ifdef RMW_UXRCE_TRANSPORT_CUSTOM
// --- micro-ROS Transports ---
#define UART_DMA_BUFFER_SIZE 2048

static uint8_t dma_buffer[UART_DMA_BUFFER_SIZE];
static size_t dma_head = 0, dma_tail = 0;
bool cubemx_transport_open(struct uxrCustomTransport * transport){
    UART_HandleTypeDef * uart = (UART_HandleTypeDef*) transport->args;
    HAL_UART_Receive_DMA(uart, dma_buffer, UART_DMA_BUFFER_SIZE);
    return true;
}

bool cubemx_transport_close(struct uxrCustomTransport * transport){
    UART_HandleTypeDef * uart = (UART_HandleTypeDef*) transport->args;
    HAL_UART_DMAStop(uart);
    return true;
}
size_t cubemx_transport_write(struct uxrCustomTransport* transport, uint8_t * buf, size_t len, uint8_t * err){
    UART_HandleTypeDef * uart = (UART_HandleTypeDef*) transport->args;

    HAL_StatusTypeDef ret;
    if (uart->gState == HAL_UART_STATE_READY){
        ret = HAL_UART_Transmit_DMA(uart, buf, len);
        while (ret == HAL_OK && uart->gState != HAL_UART_STATE_READY){
         HAL_Delay(1);
        }
        return (ret == HAL_OK) ? len : 0;
    }else{
        return 0;
    }
}
size_t cubemx_transport_read(struct uxrCustomTransport* transport, uint8_t* buf, size_t len, int timeout, uint8_t* err){
    UART_HandleTypeDef * uart = (UART_HandleTypeDef*) transport->args;
    int ms_used = 0;
    do
    {
        __disable_irq();
        dma_tail = UART_DMA_BUFFER_SIZE - __HAL_DMA_GET_COUNTER(uart->hdmarx);
        __enable_irq();
        ms_used++;
        HAL_Delay(1);
    } while (dma_head == dma_tail && ms_used < timeout);
    
    size_t wrote = 0;
    while ((dma_head != dma_tail) && (wrote < len)){
        buf[wrote] = dma_buffer[dma_head];
        dma_head = (dma_head + 1) % UART_DMA_BUFFER_SIZE;
        wrote++;
    }
    
    return wrote;
}
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
{
	if(huart==&huart2)
	{
		HAL_UART_Receive_DMA(&huart2, dma_buffer, UART_DMA_BUFFER_SIZE);
	}
}
#endif //RMW_UXRCE_TRANSPORT_CUSTOM

2.7.2、修改microros_allocators.c,动态内存分配直接使用标准库函数 malloc free等,修改后文件如下

#include <unistd.h>
#include <stdlib.h>

void *pvPortMallocMicroROS( size_t xWantedSize );
void vPortFreeMicroROS( void *pv );
void *pvPortReallocMicroROS( void *pv, size_t xWantedSize );
//size_t getBlockSize( void *pv );
void *pvPortCallocMicroROS( size_t num, size_t xWantedSize );

void * microros_allocate(size_t size, void * state){
  (void) state;
  // printf("-- Alloc %d (prev: %d B)\n",size, xPortGetFreeHeapSize());
  return malloc(size);
}
void microros_deallocate(void * pointer, void * state){
  (void) state;
  // printf("-- Free %d (prev: %d B)\n",getBlockSize(pointer), xPortGetFreeHeapSize());
  if (NULL != pointer){
    free(pointer);
  }
}
void * microros_reallocate(void * pointer, size_t size, void * state){
  (void) state;
  // printf("-- Realloc %d -> %d (prev: %d B)\n",getBlockSize(pointer),size, xPortGetFreeHeapSize());

  if (NULL == pointer){
    return malloc(size);
  } else {
    return realloc(pointer,size);
  }
}
void * microros_zero_allocate(size_t number_of_elements, size_t size_of_element, void * state){
  (void) state;
  // printf("-- Calloc %d x %d = %d -> (prev: %d B)\n",number_of_elements,size_of_element, number_of_elements*size_of_element, xPortGetFreeHeapSize());
  return calloc(number_of_elements,size_of_element);
}

2.7.3、修改main.c 文件
定义一个uint32类型全局变量ullTickCount

uint32_t ullTickCount;

在while循环前启动定时器13

  /* USER CODE BEGIN 2 */
  HAL_TIM_Base_Start_IT(&htim13);
  /* USER CODE END 2 */

在定时器13更新中断中让ullTickCount自加1,计数总毫秒数

/* USER CODE BEGIN 4 */
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
{
	if(htim==&htim13)
	{
		ullTickCount++;		
	}
}
/* USER CODE END 4 */

2.7.4、添加头文件包含
在main.c合适位置添加以下内容

/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#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>
/* USER CODE END Includes */

2.7.5、添加前置声明

/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN FunctionPrototypes */
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);
/* USER CODE END FunctionPrototypes */

2.7.5、在while前添加mirco_ros 节点的初始化

	// 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;

2.7.6、在while中添加数据发布

  /* USER CODE BEGIN WHILE */
  while (1)
  {
	    rcl_ret_t ret = rcl_publish(&publisher, &msg, NULL);
	    if (ret != RCL_RET_OK)
	    {
	      printf("Error publishing (line %d)\n", __LINE__);
	    }
	    msg.data++;
	    HAL_Delay(10);

    /* USER CODE END WHILE */
  }

2.7.7、修改microros_time.c文件
添加 #define configTICK_RATE_HZ 1000LL
将ullTickCount 传递给UTILS_NanosecondsToTimespec函数
更改后代码

#include <unistd.h>
#include <time.h>

#define configTICK_RATE_HZ 1000LL
#define MICROSECONDS_PER_SECOND    ( 1000000LL )                                   /**< Microseconds per second. */
#define NANOSECONDS_PER_SECOND     ( 1000000000LL )                                /**< Nanoseconds per second. */
#define NANOSECONDS_PER_TICK       ( NANOSECONDS_PER_SECOND / configTICK_RATE_HZ ) /**< Nanoseconds per FreeRTOS tick. */

void UTILS_NanosecondsToTimespec( int64_t llSource,
                                  struct timespec * const pxDestination )
{
    long lCarrySec = 0;

    /* Convert to timespec. */
    pxDestination->tv_sec = ( time_t ) ( llSource / NANOSECONDS_PER_SECOND );
    pxDestination->tv_nsec = ( long ) ( llSource % NANOSECONDS_PER_SECOND );

    /* Subtract from tv_sec if tv_nsec < 0. */
    if( pxDestination->tv_nsec < 0L )
    {
        /* Compute the number of seconds to carry. */
        lCarrySec = ( pxDestination->tv_nsec / ( long ) NANOSECONDS_PER_SECOND ) + 1L;

        pxDestination->tv_sec -= ( time_t ) ( lCarrySec );
        pxDestination->tv_nsec += lCarrySec * ( long ) NANOSECONDS_PER_SECOND;
    }
}

int clock_gettime( int clock_id,
                   struct timespec * tp )
{
    /* Convert ullTickCount to timespec. */
    extern uint32_t ullTickCount;
    UTILS_NanosecondsToTimespec( ( int64_t ) ullTickCount * NANOSECONDS_PER_TICK, tp );
    return 0;
}

2.7.8、添加串口printf打印支持

#include "stdio.h"
#define PUTCHAR_PROTOTYPE int __io_putchar(int ch)
PUTCHAR_PROTOTYPE
{
    HAL_UART_Transmit(&huart1 , (uint8_t *)&ch, 1, 0xFFFF);
    return ch;
}

编译无报错,自此移植完成!

3、下载测试
参考micro_ros移植到STM32F405RG 测试部分

  • 23
    点赞
  • 22
    收藏
    觉得还不错? 一键收藏
  • 1
    评论
`micro_ros_stm32cubemx_utils` 是一个用于在 STM32CubeMX 中使用 micro-ROS 的实用程序库。要使用 `micro_ros_stm32cubemx_utils`,可以按照以下步骤进行: 1. 下载 `micro_ros_stm32cubemx_utils` 库。您可以从 micro-ROS 官方网站上下载该库。 2. 将 `micro_ros_stm32cubemx_utils` 库添加到 STM32CubeMX 项目中。您可以将该库添加为外部库或将其直接复制到项目目录中。 3. 在 STM32CubeMX 中配置 micro-ROS 应用程序。您可以使用 `micro_ros_stm32cubemx_utils` 库提供的插件来自动配置 micro-ROS 应用程序,并生成必要的代码和配置文件。 4. 在 STM32CubeMX 中生成代码并使用适当的编译工具链编译和链接应用程序。 以下是一个示例代码片段,展示了如何在 STM32CubeMX 中使用 `micro_ros_stm32cubemx_utils`: ``` #include "main.h" #include "micro_ros_stm32cubemx_utils.h" int main(void) { // 初始化 micro-ROS 应用程序 micro_ros_init(); // 运行 micro-ROS 应用程序 while(1) { micro_ros_spin(); } } void Error_Handler(void) { // 发生错误时执行的代码 } #ifdef USE_FULL_ASSERT void assert_failed(uint8_t *file, uint32_t line) { // 断言失败时执行的代码 } #endif /* USE_FULL_ASSERT */ ``` 在这个示例中,我们使用 `micro_ros_stm32cubemx_utils` 库提供的 `micro_ros_init()` 和 `micro_ros_spin()` 函数来初始化和运行 micro-ROS 应用程序。该应用程序将在无限循环中运行,并使用 `micro_ros_spin()` 函数来处理 micro-ROS 消息。我们还使用 STM32CubeMX 自动生成的错误处理和断言失败处理函数来处理错误情况。

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值