ROS 2でWoL(Wake-on-LAN)したかった話
Wake-on-LANでロボット制御パソコンを起動したい
今年は例年のmicro-ROSネタから少し離れて小ネタをご紹介します。
ROS 2を動かす複数のパソコンの起動を連動させたい場合のTipsになります。
趣味で複数のロボット制御用パソコン(以下、制御PC)を搭載するロボット制御ユニットを製作しているのですが、その中で気づいたちょっとしたノウハウ[1]の紹介記事になります。
複数のパソコンで制御されるロボットシステム
少し大型のロボットシステムになると、役割分担されたいくつかの制御PCが搭載されることはよくあることかと思います。
運動制御や認識制御など、各制御PCで役割分担されたROS 2ノードを起動して、処理したデータを統合処理してロボットを動作させるイメージですね。
起動順序は大切
複数の制御PCが連携して動作するには、次のようなポイントが重要になることが多いです。
- システムの起動順序
- 電力消費の増減
- システムの時刻同期
特に複数の制御PCやデバイスを持つロボットシステムでは、起動順序を設計したくなることがほとんどです。ROS 2ではノードの実行順序を制御するために利用できる仕組みが色々と追加されていることからも重要度の高さを伺えるでしょう。
制御PCの起動順序制御とWoL
複数の制御PCを任意のタイミングで起動させるために便利なのがWoL(Wake-on-LAN)機能です。
WoLは最近のパソコン用マザーボードには広く搭載されている機能で、シャットダウン状態のパソコンへMagicPacketと呼ばれるUDPデータを格納したパケットを送信することで遠隔から電源をONすることが可能です。
実現したいこと
ここで筆者が趣味のロボット用に製作中の制御ユニットを例題に取り上げます。制御ユニットには次の2つの制御PCが内蔵されています。
- NavigationやMappingといった大きなデータを処理するApplicationの実行を担当するIntel NUC
- モータ制御や電源管理などDriver系の実行を担当するAsrock SBC
Interl NUCは小型でパワフルなのでコンパクトなロボットシステムの構築にはとても魅力的な製品なのですが、パソコン文脈の制御装置をロボットに組み込むには拡張性や消費電力の面で苦労も少なくありません。[2]
そこで、IOや常時動作が必要な機能は産業用SBCに担当させ、必要な時だけNUCを起動させてフルパワーの制御を行わせるとよいのではないかと考えました。
この制御ユニットにおいて、Driver PC
->Application PC
の順で制御PCを起動するためにWoLの機能を利用したいと考えました。
WoLの概要
WoLのMagicPacketは次のデータで構成されます。
-
0xFFFFFFFFFFFF
の先頭バイト列 - それに続くWoLで起床を要求するパソコンのMACアドレスを6回繰り返す
WoLはCPUが停止状態でもNICが自身のMACアドレス宛てのUDPパケットを解釈し、このMagicPacketを認識すると電源ON信号を発生させます。
普通のWoLパケット発行方法
Ubuntuではwakeonlan
というコマンドラインツールを使用することが普通かと思います。次のようにインストールして利用できるでしょう。
$ sudo apt install wakeonlan
$ wakeonlan 01:23:45:67:89:AB
wiresharkなどのパケットキャプチャツールで確認すると、次のようなパケット構造が確認できるはずです。WoLのデータが選択状態の部分になります。
ROS 2のAPIからWoLパケットを発行するには
さて、wakeonlanで簡単にWoLパケットを投げることができるのですが、ROS 2と連動させようと思うとシェルコマンドを呼び出す形のスッキリしないコードを書く必要がありそうです。
これをROS 2のノードから直接投げることができれば、対象の制御PCの起床確認などノード内で簡潔に書けそうな気がしませんか?😎
というわけで、ROS 2の基本パッケージに存在するAPIを利用してWoLパケット[3]を投げてみようと思います。
次の単純なコードと少しの工夫でWoL経由での制御PC起動を実現できました。
#! /usr/bin/env python
import argparse
import rclpy
from rclpy.node import Node
from std_msgs.msg import ByteMultiArray
from ros2multicast.api import send
class WolSenderNode(Node):
def __init__(self, mac_str: str):
super().__init__('wol_sender')
self.publisher_ = self.create_publisher(ByteMultiArray, 'chatter', 10)
timer_period = 0.5 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.mac_str = mac_str
def mac_to_bytes(self, mac_str):
return [int(b, 16) for b in mac_str.split(':')]
def timer_callback(self):
msg = ByteMultiArray()
head_data = self.mac_to_bytes("FF:FF:FF:FF:FF:FF")
mac_data = self.mac_to_bytes(self.mac_str)
magic_packet = head_data + mac_data * 16
send(bytes(magic_packet))
def main(args=None):
rclpy.init(args=args)
parser = argparse.ArgumentParser()
parser.add_argument('mac', type=str)
parse_args = parser.parse_args()
node = WolSenderNode(parse_args.mac)
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
このコードの注意点としては、WoLで起動する対象がネットワークで一度起動したことがある
状態である必要があります。[4]
この記事のポイントは普通は直接利用しないros2cli
のPython APIをimportしている次の行です。
from ros2multicast.api import send
ROS 2のAPIからWoLパケットを発行した!などと書きましたが、send関数の内容を見てみましょう。
def send(data, *, group=DEFAULT_GROUP, port=DEFAULT_PORT, ttl=None):
s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP)
if ttl is not None:
packed_ttl = struct.pack('b', ttl)
s.setsockopt(socket.IPPROTO_IP, socket.IP_MULTICAST_TTL, packed_ttl)
try:
s.sendto(data, (group, port))
finally:
s.close()
ごく単純なsocket通信をしているだけです!
このコードはros2multicastというROS 2でノード同士がお互いを発見するために送受信するマルチキャストUDPパケットをテストするためのツールの一部になります。
ROS 2のAPIを使った〜と言いたいだけのコードになってしまいましたね🤣
ROS/ROS 2には様々な機能があり一つ一つの関数まで把握することは困難な規模になっていますが、それぞれの機能を実現しているコードに着目すると、決して理解できない難易度ではない(そしてコードへアクセスが可能である)ことがわかる例でもあります。
仕事でも趣味でもROSを活用・応用してあれこれ作っていますが、もう少しROSのコア部分にも興味を持って貢献できたらよいなと感じた[5]カレンダーネタでした。
-
ネタ記事なので実用性はあまり期待せずにご覧ください ↩︎
-
IOをUSBから引き出すしかないとかアイドル中でも結構な電力を要求されるとか🙄 ↩︎
-
本来はブロードキャストしないといけないところをマルチキャストしているので実は似て非なるものになっているというオチです ↩︎
-
マルチキャストで送っているので通信経路上へ起動対象のMACアドレスから何らか送信させないとうまく動きません ↩︎
-
実はRTPSのuser dataやtopicなど色々な方法でWoLが反応しないか実験した末にうまく動いた内容を記事にしました。Alternative middlewareでまた盛り上がりそうなので通信実装をもっと理解しないとなぁと感じるこの頃です ↩︎
Discussion