将micro-ROS烧录到M5 Atom Matrix上

首先/首要的是

我打算在 M5 Atom Matrix 上刷入 micro-ROS。之前我尝试了其他博客中介绍的方法,但 ESP32 始终无法成功启动,一直在重启循环中。考虑到 micro-ROS 的开发进展很快,我决定记录下我的步骤备忘。

由于现在是2023年11月的方法,所以我无法确定它的有效期限。

使用的环境和软件版本

nameversionMBPIntel Core i7macOS13.6.1PlatformIO Core6.1.11PlatformIO Home3.4.4ROS2Iron IrwiniUbuntu22.04Parallels Desktop19.1.0

使用 PlatformIO 创建项目

假设Visual Studio Code中已经安装了PlatformIO.

基本上,官方网站上有详细的步骤说明。按照这些说明进行操作,就可以正常运行。

如果您正在使用Arduino IDE,请参考下面的内容。

如果还没有使用binutils,将进行安装。

brew install binutils

然而,仅仅安装是无法成功构建的。从M1Mac开始,安装路径已经从/usr/local/更改为/opt/homebrew/。PlatformIO似乎也正式使用了新版本。因为不知道如何进行更改,所以决定使用符号链接来应对。

cd /opt/homebrew/opt
sudo ln -s ../../../usr/local/opt/binutils binutils

我們將平台.ini編輯成以下的格式。由於缺少Wire於lib_deps中,將會導致編譯錯誤,所以請不要省略。

我已经添加了M5 Atom S3的设置。
我已经改用M5Unified了。不再需要Wire。
[env:m5stack-atom]
platform = espressif32
board = m5stack-atom
framework = arduino
lib_deps = 
    fastled/FastLED@^3.6.0
  	m5stack/M5Unified@^0.1.10
    https://github.com/micro-ROS/micro_ros_platformio
board_microros_distro = iron
board_microros_transport = serial

[env:m5stack-atoms3]
platform = espressif32
board = m5stack-atoms3
framework = arduino
lib_deps = 
	fastled/FastLED@^3.6.0
	m5stack/M5Unified@^0.1.10
	https://github.com/micro-ROS/micro_ros_platformio
build_flags =
	'-D ARDUINO_USB_MODE=1'
	'-D ARDUINO_USB_CDC_ON_BOOT=1'
board_microros_distro = iron
board_microros_transport = serial

如果不指定board_microros_distro,则将使用默认值。

    • humble

iron (default value)
rolling

board_microros_transport是从Atom传输数据的方法。我们使用USB串口进行传输。请根据这个设置来编写源代码。具体的写法请参考README.md文件。

serial (default value)
wifi
wifi_nina
native_ethernet
custom

编码。(Bian1ma3)

我将复制粘贴这个例子。这次我使用Atom Matrix。由于IMU搭载了MPU6886,所以我将尝试更改代码来发布三轴重力加速度计和三轴陀螺仪的数据。

#include <Arduino.h>
#include <M5Unified.h>
#include <micro_ros_platformio.h>

#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>

#include <sensor_msgs/msg/imu.h>

#if !defined(MICRO_ROS_TRANSPORT_ARDUINO_SERIAL)
#error This example is only avaliable for Arduino framework with serial transport.
#endif

rcl_publisher_t publisher;
sensor_msgs__msg__Imu msg;

rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;

#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}

// Error handle loop
void error_loop() {
  while(1) {
    delay(100);
  }
}

void timer_callback(rcl_timer_t * timer, int64_t last_call_time) {
  RCLC_UNUSED(last_call_time);

  if (timer != NULL) {
    float linear_acceleration_x = 0.0;
    float linear_acceleration_y = 0.0;
    float linear_acceleration_z = 0.0;
    float angular_velocity_x = 0.0;
    float angular_velocity_y = 0.0;
    float angular_velocity_z = 0.0;

    M5.IMU.getGyroData(&angular_velocity_x, &angular_velocity_y, &angular_velocity_z);
    M5.IMU.getAccelData(&linear_acceleration_x, &linear_acceleration_y, &linear_acceleration_z);

    msg.linear_acceleration.x = linear_acceleration_x;
    msg.linear_acceleration.y = linear_acceleration_y;
    msg.linear_acceleration.z = linear_acceleration_z;
    msg.angular_velocity.x = angular_velocity_x;
    msg.angular_velocity.y = angular_velocity_y;
    msg.angular_velocity.z = angular_velocity_z;

    RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
  }
}

void setup() {
  auto cfg = M5.config();
  M5.begin(cfg);

  // Configure serial transport
  Serial.begin(115200);
  set_microros_serial_transports(Serial);
  delay(2000);

  allocator = rcl_get_default_allocator();

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

  // create node
  RCCHECK(rclc_node_init_default(&node, "micro_ros_platformio_node", "", &support));

  // create publisher
  RCCHECK(rclc_publisher_init_default(
    &publisher,
    &node,
    ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, Imu),
    "pub_imu"));

  // create timer,
  const unsigned int timer_timeout = 1000;
  RCCHECK(rclc_timer_init_default(
    &timer,
    &support,
    RCL_MS_TO_NS(timer_timeout),
    timer_callback));

  // create executor
  RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
  RCCHECK(rclc_executor_add_timer(&executor, &timer));
}

void loop() {
  delay(100);
  RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
}

闪光灯

点击PlatformIO的上传按钮来进行固件烧写。在vscode的左下角附近,有一排按钮。

micro_ROS代理

我尝试在macOS上运行,但失败了。首先,ROS2不支持macOS。因此,提供了使用docker轻松运行代理的方法。但是,在macOS上无法将USB串行端口挂载到docker。可能是qemu的设置或其他问题,但我决定直接在Ubuntu上运行。由于我没有Ubuntu机器,所以我在Parallels Desktop上安装了Ubuntu 22.04。

安装ROS2 Iron Irwini版。

按照公式文档进行操作就没有问题。我使用apt安装了ros-iron-desktop。

micro_ROS 构建

执行micro_ros_setup的构建方法。

source /opt/ros/iron/setup.bash
mkdir uros_ws && cd uros_ws
git clone -b iron https://github.com/micro-ROS/micro_ros_setup.git src/micro_ros_setup
rosdep update && rosdep install --from-paths src --ignore-src -y
colcon build
source install/local_setup.bash

准备USB串行串口

使用M5 Atom将其连接,通过Parallels Desktop的设置将其配置为可供客户操作系统使用。只要有/dev/ttyUSB0即可。

$ ls -l /dev/ttyUSB0 
crw-rw---- 1 root dialout 188, 0 Nov  6 11:24 /dev/ttyUSB0

只有当在ls中显示时,才能使用dialout组。我会将用户添加到该组中。

$ sudo adduser [username] dialout

重新启动一次或重新登录。

使用id命令确认是否显示了dialout。

$ id
uid=1000(username) gid=1000(username) groups=1000(username),4(adm),20(dialout),24(cdrom),27(sudo),30(dip),46(plugdev),122(lpadmin),134(lxd),135(sambashare)

微_ROS_Agent 构建

执行micro_ROS_Agent的构建方法。

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

执行

我会在您在构建中使用的终端上执行代理程序。

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

运行另一个终端,并确认有一个主题。如果/pub_imu存在即为成功。

$ source /opt/ros/iron/setup.bash
$ ros2 topic list
/parameter_events
/pub_imu
/rosout

让我们显示收到的数据内容。

$ ros2 topic echo /pub_imu

左侧终端是micro_ROS_Agent,右侧终端是主题显示。可以看出每秒发送一次。

run_micro-ros-agent.png

如果要在docker上运行的话

在Ubuntu上按照官方文档安装docker,然后进行执行。

$ sudo docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:iron serial --dev /dev/ttyUSB0 -v6

如果要在ROS2上进行开发,则似乎创建一个非docker的ROS2环境会更快一些。

故障排除 (Guzhang paichu)

当您刚刚刷新了M5 Atom设备或者连接到Parallels Desktop之后,串口未能传输数据。请按下M5 Atom的复位按钮。当与代理程序断开连接时也需要进行复位。是否一定需要复位,目前还不太清楚。

bannerAds