えいあーるれいの技術日記

ROS2やM5 Stack、Ubuntuについて書いています

microROS-ArduinoのM5Atom用設定(ESP32・ROS2)

本当はもう少しあとにしようかなとか思っていたのですが、後輩に「先輩の記事見たんですが、ros2arduinoを使ったほうがいいのかなーー」と言われてしまい焦ったので、とりあえず今のうちからmicroROSを推しておこうと思います。


…なぜ知っているし。

microROSとは

microROSとは、実質公式のマイコン向けROS2です。

ArduinoやSTM32CubeMX、Raspberry Pi Picoなどのさまざまなプラットフォームに対応しており、(Agentサーバが必要になりますが)ネットワーク内のデバイスと自由に相互通信することができるようになります。

microROSはrclc-client libraryをベースにしてさまざまなミドルウェアを統合したライブラリです。マイコンによるUDPTCPを使ったDDS通信をサポートするMicroXRCE-DDSや、POSIXベースのRTOSに対応しています。

ros2arduinoからの乗り換え

およそ1年半前にROS2をはじめて触った頃にマイコン向けのROS2で探したところ使いやすかったライブラリがros2arduinoでした。見てわかるとおり現在はほとんど開発されていませんが…

github.com

microROSと比べても記法がC++寄りで分かりやすく、自分がほしかった機能を満たすくらいには使えたので1年くらいはこのライブラリを使っていました。

ただ、sensor_msgs/Imu型のデータがどうしても送れなかったりpub-subを増やしすぎると動かなくなったりしたので、これらの悩みを解決できるmicroROSに乗り換えました。

mROS2というagentなしのすごいマイコン向けROS2もあるようなのでマイコンが手に入れば使ってみたいですね。

micoROS-Arduino + ESP32の使いかた

microROSはさまざまなボードをサポートしているため、ボードの数だけチュートリアルがありますが、ここではM5Atom(ESP32-Pico)とPlatformIOを使った開発例を紹介したいと思います。

BugC + PS5の組み合わせもこのチュートリアルにしたがって作成できます。近いうちにレシピを公開したいです。

環境

1. PlatformIOを開く

次の画面は、ExtensionsからPlatfomIOをインストールしてVSCodeのリロードが終わったあとの画面です。

f:id:Ray_ar:20220407095755p:plain

プロジェクトの新規作成を行います。

  • ① PlatformIOのアイコンをクリック
  • ② PIO Home/Openをクリック
  • ③ + New Projecttをクリック

f:id:Ray_ar:20220407095955p:plain

すると、上のような画像が表示されます。Project Wizardに次の内容を記入します。

  • Name:プロジェクト名
  • Board:対象ボード。M5Atomは対象に含まれていないもののCPUがM5Stick-Cと同じなので、M5Stick-Cを選択する。
  • Framework:言語。Arduino言語を使用するため、Arduino Frameworkを選択する。
  • Location:ファイルが格納される場所

すべて記載したらFinishボタンを押してプロジェクトが作成されるまで待つ。

2. platformio.iniの設定

microROS-Arduinoにはライブラリの組み合わせがあるようで、すべて最新でOK!…とはいきません。そこで、PlatformIOの利点であるビルド時にライブラリを自動インストールする機能を使います。

f:id:Ray_ar:20220407104326p:plain

プロジェクトウィザード終了後にplatformio.iniが開くので次のコードをコピペします。

gist.github.com

もしかしたら、Git由来のライブラリがアップデートされた場合にコンパイルに失敗する可能性もあるかもしれないので、その場合は適宜修正してください。

コメントアウトしている箇所は、ESP32-devとM5Stick-Cの場合のライブラリを使いたいとき用です。その場合、M5Atom依存のライブラリをコメントアウトして対象のライブラリのコメントアウトを外してください。

3. main.cppの編集

MPU6886のimuの内容を送信するサンプルプログラムを以下に示します。

※ROS2のエラー処理については簡単のために省略しています。

#include <Arduino.h>
#include "WiFi.h"

#include <M5Atom.h>

// microros ===================================================================
#include <micro_ros_arduino.h>

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

#include <sensor_msgs/msg/imu.h>

rclc_executor_t executor;
rcl_publisher_t publisher;
sensor_msgs__msg__Imu msg;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;

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

  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;

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

void setup()
{
  M5.begin(true, true, true);
  M5.IMU.Init();

  // int agent_id = 2000;
  // set_microros_wifi_transports("ssid", "pass", "ip", agent_id);
  set_microros_transports();

  delay(2000);

  allocator = rcl_get_default_allocator();

  // create init_options
  rclc_support_init(&support, 0, NULL, &allocator);
  rclc_node_init_default(&node, "micro_ros_node", "", &support);
  rclc_publisher_init_default(&publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, Imu), "pub_imu");

  const unsigned int timer_timeout = 1000;
  rclc_timer_init_default(&timer, &support, RCL_MS_TO_NS(timer_timeout), timer_callback);
  rclc_executor_init(&executor, &support.context, 1, &allocator);
  rclc_executor_add_timer(&executor, &timer);
}

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

あとは左下付近にあるUploadボタンを押してアップロードします。Permission Errorの場合は管理者権限を与えるとうまく動きます。

/dev/ttyUSB0に接続されている場合、大体はsudo chmod 777 /dev/ttyUSB0で解決します。(dockerの場合も同様です。)

4. microROS-agentの起動

micorROS-agentはDockerを使った起動が最も楽です。ここではUSBポート経由のシリアル接続の場合の実行コマンドを示します。

docker run -it --rm -v /dev:/dev --privileged --net=host microros/micro-ros-agent:galactic serial --dev /dev/ttyUSB0 --baud 115200

他のインタフェースを使用する際はこのページを参考にコマンドを入力してください。


接続に成功すると次のようなログ画面になります。

f:id:Ray_ar:20220407104455p:plain

あとは別のターミナルでros2 topic echo /pub_imuを入力してトピックを受信すれば、1秒ごとにIMUのデータが流れてきます。