概要(前提)
本検証では、これまで個別に実施してきた以下の要素を統合し、ROS2環境から実機ロボットを制御できるかを確認しました。
- Arduino UNO R4 WiFiを用いた制御基板の検証
- タミヤ製パーツによる車体構築の検証
- Ubuntu 24環境におけるROS2 Jazzyの動作確認
これらを前提として、ROS2でのロボットの移動速度(前進・回転)を指示する主要なトピック である/cmd_velを用いて、WiFi経由で車体を駆動する統合検証を実施しました。

このロボットをROS2のノードを経由して操作します。ROS2ノードを起動した状態で以下のようにコマンドラインからROS2コマンドで動作(cmd_vel)をpublishして動作を指示します。

構成
本検証の構成は以下の通りです。
ROS2(Ubuntu24 + Jazzy)
↓ /cmd_vel
ROS2ノード(cmd_vel → コマンド変換)
↓ WiFi
Arduino UNO R4 WiFi(サーバ)
↓
モータードライバ(TB6612)
↓
タミヤ車体(差動二輪)
各構成要素
- ROS2ノード
/cmd_velをsubscribeし、前後・左右・停止のコマンドへ変換して送信 - Arduino UNO R4 WiFi
WiFiサーバとして動作し、受信したコマンドに応じてモーターを制御 - 車体
タミヤ製パーツを用いた差動二輪構成 - センサー
超音波距離センサーにより、一定距離での停止制御を実装
実装内容
ROS2ノード
/cmd_velの値に応じて、以下のコマンドに変換し、TCP通信でArduinoへ送信します。
- F:前進
- B:後退
- L:左旋回
- R:右旋回
- S:停止
最小構成として、速度値の細かい調整は行わず、動作確認を優先しています。またArduino側のIPアドレスも固定で記述しています。これをbuildしてROS2ノードとして稼働します。
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
import socket
ROBOT_IP = "192.168.xxx.xxx" # ← ArduinoのIP
ROBOT_PORT = 80
class CmdVelToWiFi(Node):
def __init__(self):
super().__init__('cmdvel_to_wifi')
self.subscription = self.create_subscription(
Twist,
'/cmd_vel',
self.listener_callback,
10
)
self.last_cmd = None # 無駄送信防止
def send_command(self, cmd):
try:
with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as s:
s.connect((ROBOT_IP, ROBOT_PORT))
s.send((cmd + "\n").encode())
except Exception as e:
self.get_logger().error(f"Send error: {e}")
def listener_callback(self, msg):
linear = msg.linear.x
angular = msg.angular.z
# ---- コマンド変換 ----
if linear > 0:
cmd = 'F'
elif linear < 0:
cmd = 'B'
elif angular > 0:
cmd = 'L'
elif angular < 0:
cmd = 'R'
else:
cmd = 'S'
# ---- 同じコマンドは送らない ----
if cmd != self.last_cmd:
self.get_logger().info(f"Send: {cmd}")
self.send_command(cmd)
self.last_cmd = cmd
def main(args=None):
rclpy.init(args=args)
node = CmdVelToWiFi()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
Arduino側プログラム
Arduino UNO R4 WiFiでは、WiFiサーバとして待ち受けを行い、受信したコマンドに応じてモーター制御を行います。これはあくまでもサンプルプログラムです。モーターの向きや配線で向きや速度を調整する必要があります。SSIDやパスワードも固定で記述しています。
また、超音波センサーによる距離測定を行い、一定距離未満の場合はコマンドに関係なく強制停止する安全機能を実装しています。
#include <WiFiS3.h>
#include "Grove_Motor_Driver_TB6612FNG.h"
#include <Wire.h>
// ===== WiFi設定 =====
char ssid[] = "YOUR_SSID";
char pass[] = "YOUR_PASS";
WiFiServer server(80);
// ===== モーター =====
MotorDriver motor;
// ===== 超音波 =====
#define ULTRASONIC_PIN 5
#define SAMPLE_SIZE 11
long measurements[SAMPLE_SIZE];
// ===== 状態 =====
char currentCommand = 'S'; // 初期停止
// -------------------- 初期化 --------------------
void setup() {
Serial.begin(115200);
Wire.begin();
motor.init();
WiFi.begin(ssid, pass);
Serial.print("Connecting WiFi");
while (WiFi.status() != WL_CONNECTED) {
delay(1000);
Serial.print(".");
}
Serial.println("\nConnected!");
Serial.println(WiFi.localIP());
server.begin();
}
// -------------------- モーター制御 --------------------
void forward() {
motor.dcMotorRun(MOTOR_CHA, 150);
motor.dcMotorRun(MOTOR_CHB, 150);
}
void back() {
motor.dcMotorRun(MOTOR_CHA, -150);
motor.dcMotorRun(MOTOR_CHB, -150);
}
void left() {
motor.dcMotorRun(MOTOR_CHA, -150);
motor.dcMotorRun(MOTOR_CHB, 150);
}
void right() {
motor.dcMotorRun(MOTOR_CHA, 150);
motor.dcMotorRun(MOTOR_CHB, -150);
}
void stopMotor() {
motor.dcMotorStop(MOTOR_CHA);
motor.dcMotorStop(MOTOR_CHB);
}
void brake() {
motor.dcMotorBrake(MOTOR_CHA);
motor.dcMotorBrake(MOTOR_CHB);
}
// -------------------- 超音波 --------------------
long getDistance() {
pinMode(ULTRASONIC_PIN, OUTPUT);
digitalWrite(ULTRASONIC_PIN, LOW);
delayMicroseconds(2);
digitalWrite(ULTRASONIC_PIN, HIGH);
delayMicroseconds(5);
digitalWrite(ULTRASONIC_PIN, LOW);
pinMode(ULTRASONIC_PIN, INPUT);
long duration = pulseIn(ULTRASONIC_PIN, HIGH, 30000);
if (duration == 0) return -1;
return duration / 29 / 2;
}
void sortArray(long arr[], int size) {
for (int i = 0; i < size - 1; i++) {
for (int j = i + 1; j < size; j++) {
if (arr[i] > arr[j]) {
long tmp = arr[i];
arr[i] = arr[j];
arr[j] = tmp;
}
}
}
}
long getMedianDistance() {
int count = 0;
while (count < SAMPLE_SIZE) {
long d = getDistance();
if (d > 0) {
measurements[count] = d;
count++;
}
delay(10);
}
sortArray(measurements, SAMPLE_SIZE);
return measurements[SAMPLE_SIZE / 2];
}
// -------------------- コマンド実行 --------------------
void executeCommand() {
switch (currentCommand) {
case 'F': forward(); break;
case 'B': back(); break;
case 'L': left(); break;
case 'R': right(); break;
case 'S': stopMotor(); break;
}
}
// -------------------- メインループ --------------------
void loop() {
// ===== コマンド受信 =====
WiFiClient client = server.available();
if (client) {
String cmd = client.readStringUntil('\n');
cmd.trim();
if (cmd.length() > 0) {
currentCommand = cmd.charAt(0);
Serial.print("CMD: ");
Serial.println(currentCommand);
}
client.stop();
}
// ===== 距離チェック =====
long distance = getMedianDistance();
Serial.print("Distance: ");
Serial.println(distance);
// ===== 安全優先 =====
if (distance > 0 && distance < 15) {
brake(); // 強制停止
} else {
executeCommand(); // 通常動作
}
delay(50);
}
※本検証では動作確認を優先し、cmd_velから前後・左右・停止の単純なコマンドに変換して制御していますが、実際の移動ロボットではcmd_vel(速度指令)をもとに各車輪の回転数(RPM)やPWM値へ変換し、より連続的な速度制御を行います。
検証内容
まずは、ROS2ノードをビルドして事前に起動しておきます。
その上で以下の動作を確認しました。
/cmd_velの送信による前進・後退・左右旋回- 停止コマンドによる動作停止
- 超音波センサーによる一定距離(約15cm)での緊急停止
- ネットワーク越しの制御が安定して動作すること
コマンドは以下のようにros2 topic pubで送信し、動作確認を行いました。この場合はずっと動いたままになるので、続けて “{linear: {}}” を指定して停止します。
ros2 topic pub --once /cmd_vel geometry_msgs/Twist "{linear: {x: 1.0}}"
結果
本検証により、ROS2の/cmd_velを用いて、WiFi経由で実機ロボットを制御できることを確認しました。
また、センサーによる停止制御を組み合わせることで、単純な遠隔操作に加えて基本的な安全機能も実装可能であることを確認しました。
技術的ポイント
- ROS2の標準インターフェース(cmd_vel)をそのまま利用
- マイコン側はシンプルなコマンド受信に限定
- センサー制御をローカル側で優先処理(安全設計)
- ネットワーク越しでも安定した制御が可能
位置づけ(ロボット実機の統合検証①)
本検証は、以下の要素を統合した初期段階の統合検証として位置付けます。
- ROS2による外部制御
- WiFiによる通信
- 実機ロボットの駆動
- センサーによる基本的なフィードバック
今後の展開
本構成をベースとして、以下の拡張を予定しています。
- rosbridgeを用いたブラウザからの操作(Web連携)
- Blocklyによる動作制御(非エンジニア向け検証)
これにより、操作インターフェースの抽象化および利用者層の拡張を図ります。
まとめ
本検証により、個別に構築した要素(車体・制御・ROS2環境)を統合し、/cmd_velによる実機制御が実現可能であることを確認しました。


