| 特性 | 完整ROS2节点 | 微ROS客户端节点 |
|---|---|---|
| 最小RAM需求 | ≥ 512KB(含DDS堆) | ≈ 12KB(含传输层缓冲) |
| 最小Flash需求 | ≥ 2MB | ≈ 100KB(带典型发布器) |
| 实时OS依赖 | Linux或RTOS | FreeRTOS/Zephyr/裸机 |
| DDS协议栈 | FastDDS/GurumDDS | DDS-XRCE精简协议 |
| 跨网络能力 | 有线/WiFi/共享内存 | UDP/串口/蓝牙(需传输插件) |
rclc_executor_spin_some()。# 假设已在工程根目录下执行
git clone -b foxy https://github.com/micro-ROS/micro_ros_stm32cubemx_generators.git
# 将库路径填入CubeMX的额外工具链路径
# 生成工程后会自动包含:
# micro_ros_stm32cubemx_generators/micro_ros_src/
# micro_ros_stm32cubemx_generators/micro_ros_lib/
在CubeMX中需要额外配置:
1. 使能FreeRTOS(CMSIS_V1或V2均可,微ROS需要其定时器和互斥量)
2. 配置一个UART或USART实例(用于与Agent通信)
3. 堆栈大小建议:至少为微ROS留出4KB的任务栈,DMA缓冲区各1KB
如果生成的工程报`HAL_UART_Receive_DMA`未定义,直接换成轮询接收模式即可——这在低速传感器采集场景中完全够用,我经常在小批量原型上这么干,能节省一个DMA通道。
open_cb:初始化传输层,例如开启UART外设时钟write_cb:发送数据。原型:bool (*write_cb)(void* buf, size_t len, uint8_t* err)read_cb:接收数据。原型:bool (*read_cb)(void* buf, size_t len, int32_t* timeout)// 示例:写函数实现(STM32 UART)
static bool transport_write(void* transport, uint8_t* buf, size_t len, uint8_t* err) {
if (HAL_UART_Transmit_DMA(&huart1, buf, len) != HAL_OK) {
*err = 1;
return false;
}
return true;
}
void main(void) {
HAL_Init();
SystemClock_Config();
MX_GPIO_Init();
MX_USART1_UART_Init(); // 微ROS代理通信串口
MX_FREERTOS_Init(); // 包含微ROS任务
osKernelStart();
}
void micro_ros_task(void* arg) {
// 1. 设置传输层
static uxr_transport_t transport;
uxr_set_transport_custom(&transport, 0, transport_open, transport_close,
transport_write, transport_read);
// 2. 初始化微ROS客户端
uxr_session_t session = uxr_init_session(&transport, 0x01, 0x00);
while (!uxr_create_session(&session)) { osDelay(100); }
// 3. 创建RCL节点
rcl_allocator_t alloc = rcl_get_default_allocator();
rclc_support_t support;
rclc_support_init(&support, 0, NULL, &alloc);
rclc_node_init_default(&node, "stm32_node", "", &support);
rclc_publisher_init_default(&pub, &node, ROSIDL_GET_MSG_TYPE(int32), "motor_rpm");
// 4. 主循环发布
int32_t rpm = 0;
while (1) {
rpm = get_rpm_from_encoder(); // 用户函数
rcl_publish(&pub, &rpm, NULL);
rclc_executor_spin_some(&executor, 10); // 处理入站订阅
osDelay(20); // 50Hz发布
}
}
注意上面代码中`rclc_executor_spin_some`的调用——这是微ROS中订阅回调驱动的核心。如果在FreeRTOS任务里不加这一行,则Agent发来的设置命令会一直堆积在接收缓冲中得不到处理。
std_msgs/msg/Int32就不要在Agent那边用std_msgs/msg/Int64。找一个STM32F4开发板,按上述步骤完成微ROS客户端移植,实现一个以5Hz频率发布板载温度传感器(STM32内部温度)的话题。
检验方式:在PC上运行 ros2 topic echo /stm32_temperature 查看是否有数据输出。再尝试在PC上发布一个 std_msgs/msg/UInt8 话题 /led_control,在MCU侧订阅并点灭板载LED(注意:LED通常高电平点亮还是低电平?)。
write_cb 在用户代码中是同步阻塞的,这句话对吗?