ESP32-S3 + PlatformIOでmicro-ROS通信
以前、Raspberry Pi Picoを使ったmicro-ROS通信について投稿しました。
今回はESP32でmicro-ROS通信をやってみました。
Platform IOプロジェクトの作成
前回espidfフレームワークでWifi通信をやりました。
今回はPlatformIO向けのmicro-ROSコンポーネントライブラリを使います。
注意点としては、利用するフレームワークはarduinoフレームワークです。espidfではないです。当初前回の流れでespidfのプロジェクトを作成したところ、ライブラリのビルドで失敗して、かなりの時間を溶かしました。。
作成後、platformio.iniを編集します。lib_depsで上記のライブラリのリポジトリをしてするのがポイントです。ファイルを保存すると自動的にプロジェクト配下の.pioフォルダにダウンロードされて必要な依存モジュールのダウンロードやビルドが開始します。
ここで、フレームワークをespidfにしていると、コンパイルエラーが発生するので注意です。
[env:esp32-s3-devkitc-1]
platform = espressif32
board = esp32-s3-devkitc-1
framework = arduino
upload_speed = 2000000
monitor_speed = 115200
lib_deps =
https://github.com/micro-ROS/micro_ros_platformio
board_microros_distro = humble
board_microros_transport = wifi
build_flags =
-DMICRO_ROS_TRANSPORT_UDP
-DARDUINOJSON_ENABLE_ARDUINO_STRING=1
-DARDUINOJSON_USE_LONG_LONG=1
-DARDUINOJSON_DECODE_UNICODE=1
-DARDUINOJSON_ENABLE_NAN=1
board_microros_distroでディストリビューションを指定して、board_microros_transportでwifiを指定します。これが2個目のポイントです。micro-ROSの通信方式はシリアル通信がデフォルトなので、wifiを指定します。
micro-ROS通信を使った実装
今回もPicoの時と同じようにパブリッシュとサブスクライブを実装します。
ROS周りはほとんど同じです。
arduinoフレームワークを利用しているので、setupとloopを実装します。
set_microros_wifi_transportsでマクロを指定してますがここでWifiのアクセスポイントやパスワードなどの通信設定をします。
//secret.h
#define WIFI_SSID "MySSID"
#define WIFI_PASSWORD "MyPassword"
#define MICRROS_AGENT_IP "192.168.0.100"
#define MICROROS_AGENT_PORT 8888
パブリッシュについてはタイマーコールバック内で送信することにしてます。サブスクライブも同様でコールバックを定義します。Picoの時の実装とほぼ同じかと思います。
void setup() {
Serial.begin(115200);
// Wifiの設定を行う
IPAddress agent_ip;
agent_ip.fromString(MICRROS_AGENT_IP);
uint16_t agent_port = MICROROS_AGENT_PORT;
set_microros_wifi_transports(WIFI_SSID, WIFI_PASSWORD, agent_ip, agent_port);
delay(2000);
// NTPサーバーに接続して時間を調整する
configTime(0, 0, "pool.ntp.org", "time.nist.gov");
delay(3000);
allocator = rcl_get_default_allocator();
rclc_support_init(&support, 0, NULL, &allocator);
rcl_node_t node;
rclc_node_init_default(&node, "esp32_node", "", &support);
//publisherの作成
rclc_publisher_init_best_effort(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"/esp32_topic");
// Subscriber の作成
rclc_subscription_init_best_effort(
&subscriber,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"/esp32_topic2"
);
// タイマーの作成(1秒ごとに timer_callback 実行)
rclc_timer_init_default(&timer, &support, RCL_MS_TO_NS(1000), timer_callback);
// Executor の作成
int callback_size = 2;
executor = rclc_executor_get_zero_initialized_executor();
rclc_executor_init(&executor, &support.context, callback_size, &allocator);
rclc_executor_add_subscription(&executor, &subscriber, &sub_msg, &subscription_callback, ON_NEW_DATA);
rclc_executor_add_timer(&executor, &timer);
}
loopについては以下だけです。
void loop() {
// Executor をスピン(サブスクライバーとタイマーの処理を実行)
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
}
パブリッシュについては、タイマーコールバック内で現在時間をInt32型のメッセージとして送信してます。
サブスクライブはInt32型のメッセージを受信したらprintfでダンプしてます。
#include <Arduino.h>
#include <WiFi.h>
#include <micro_ros_platformio.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <std_msgs/msg/int32.h>
#include <time.h>
#include "secret.h"
rcl_publisher_t publisher;
std_msgs__msg__Int32 pub_msg;
rcl_subscription_t subscriber;
std_msgs__msg__Int32 sub_msg;
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;
// タイマーコールバック関数(1秒ごとに実行)
void timer_callback(rcl_timer_t *timer, int64_t last_call_time) {
time_t now = time(NULL);
pub_msg.data = static_cast<int32_t>(now);
// メッセージをパブリッシュ
rcl_ret_t ret = rcl_publish(&publisher, &pub_msg, NULL);
if (ret == RCL_RET_OK) {
Serial.printf("Published UNIX time: %d\n", pub_msg.data);
} else {
Serial.printf("rcl_publish failed: %d\n", ret);
}
}
// サブスクライバーのコールバック関数
void subscription_callback(const void *msgin) {
const std_msgs__msg__Int32 *msg = (const std_msgs__msg__Int32 *)msgin;
Serial.printf("Received message: %d\n", msg->data);
}
ビルドしたらESP32に書き込みます。アップロードしたらすぐに処理が開始しますが、エージェントが起動してないとエラーになると思います。
micro-ROS エージェントのセットアップ
Ubuntu22.04でビルドは確認してます。ROS2 humbleをインストールすることが前提です。
任意の場所にmicroros_wsを作成してその中にmicro_ros_setup リポジトリをクローンしたら、エージェントをビルドするところまで実施します。
source /opt/ros/humble/setup.bash
mkdir microros_ws
cd microros_ws
git clone -b $ROS_DISTRO https://github.com/micro-ROS/micro_ros_setup.git src/micro_ros_setup
rosdep install --from-paths src --ignore-src -y
colcon build
source install/local_setup.bash
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 udp4 --port 8888
[1740378724.307047] info | UDPv4AgentLinux.cpp | init | running... | port: 8888
[1740378724.307336] info | Root.cpp | set_verbose_level | logger setup | verbose_level: 4
ROS2通信の確認
エージェントが起動したら、ESP32のリセットまたは電源再投入させてエージェントと通信できるか確認します。
ESP32でノードやトピックが登録されると、エージェントのコンソールに表示される。
[1740381818.567865] info | Root.cpp | create_client | create | client_key: 0x60F52EF3, session_id: 0x81
[1740381818.567953] info | SessionManager.hpp | establish_session | session established | client_key: 0x60F52EF3, address: 192.168.2.2:47138
[1740381818.586567] info | ProxyClient.cpp | create_participant | participant created | client_key: 0x60F52EF3, participant_id: 0x000(1)
[1740381818.592160] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x60F52EF3, topic_id: 0x000(2), participant_id: 0x000(1)
[1740381818.595781] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x60F52EF3, publisher_id: 0x000(3), participant_id: 0x000(1)
[1740381818.599956] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x60F52EF3, datawriter_id: 0x000(5), publisher_id: 0x000(3)
[1740381818.605082] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x60F52EF3, topic_id: 0x001(2), participant_id: 0x000(1)
[1740381818.608700] info | ProxyClient.cpp | create_subscriber | subscriber created | client_key: 0x60F52EF3, subscriber_id: 0x000(4), participant_id: 0x000(1)
[1740381818.615315] info | ProxyClient.cpp | create_datareader | datareader created | client_key: 0x60F52EF3, datareader_id: 0x000(6), subscriber_id: 0x000(4)
ros2コマンドで以下を確認してみる。
ノード一覧
source install/local_setup.bash
ros2 node list
/esp32_node
トピック一覧
ros2 topic list
/esp32_topic
/esp32_topic2
:
トピック詳細
ros2 topic info /esp32_topic
Type: std_msgs/msg/Int32
Publisher count: 1
Subscription count: 0
ESP32がパブリッシュしている内容をサブスクライブしてみる。
ros2 topic echo /esp32_topic
data: 1740379720
---
data: 1740379721
---
data: 1740379722
---
ESP32がサブスクライブしているトピックにメッセージを送信してみる。
ros2 topic pub /esp32_topic2 std_msgs/msg/Int32 "{data: 42}"
ESP32のシリアルモニターでESP32上での送受信内容を確認する。
パブリッシュとサブスクライブの内容が同じタイミングなので交互に表示される。
Published UNIX time: 1740382068
Received message: 42
Published UNIX time: 1740382069
Received message: 42
Published UNIX time: 1740382070
Received message: 42
Published UNIX time: 1740382071
Received message: 42
Published UNIX time: 1740382072
Received message: 42
上記のサンプルはGithubで公開中
Discussion