HALNAは外部からの通信でコマンドでの操作が可能です。また、付属のコントローラーを用いてリアルタイムでの操作とコマンドを打つことができます。
また、メッセージフォーマットを公開することでお客様自身がお持ちのプラットフォームから簡単に操作できるようにしました。
このドキュメントでは、通信仕様から現在ロボット側で対応できるコマンド一覧をフォーマットも含めて公開しています。
HALNAロボットとサーバー間の通信は、セキュアなWebソケット(wss
)を使用します。データはJSON形式でやり取りされ、リアルタイムかつ双方向の通信を実現します。
wss
) 通信通信は以下のエンドポイントを通じて確立されます:
wss://[サーバーアドレス]:[ポート番号]/[デスティネーション]/[ロボット名]/
- サーバーアドレス: 接続先のサーバーのIPアドレスまたはドメイン名。
- ポート番号: サーバーがリッスンしているポート番号。デフォルトでは5000
を使用します。
- デスティネーション: 通信の目的地を示す識別子。
- ロボット名: ロボットごとのユニークな名前。
セキュアな通信を行うため、SSL/TLS暗号化が施された
wss
プロトコルを使用します。必要に応じて、SSL証明書の検証設定を行ってください。
通信でやり取りされるデータは、すべてJSON形式で構造化されています。これにより、さまざまなプログラミング言語やプラットフォームで容易にパースおよび生成が可能です。
基本的なメッセージフォーマットは以下の通りです:
{
"sender": "送り側の名前",
"timestamp": "現在時刻",
"msgtype": "メッセージタイプ",
// その他のフィールドはメッセージタイプに依存
}
- sender: メッセージを送信するエンティティの名前(ロボット名またはサーバー名)。
- timestamp: メッセージ送信時のタイムスタンプ。ISO8601形式などの標準的な日時形式を推奨します。
- msgtype: メッセージの種類を示す識別子。詳細はメッセージフォーマットセクションを参照してください。
self.socket.ws = websocket.WebSocketApp(
"wss://%s:%s/%s/%s/"
% (self.server_address, self.port_number, self.destination, self.robot_name),
on_message=self.on_message_received,
on_open=self.on_open,
on_error=self.on_error,
on_close=self.on_close
)
ロボットはまず、https://サーバーアドレス:ポート番号/デスティネーション/ロボット名
にアクセスします。
ex) https://192.168.1.1:5000/sample/robot1
{<ベースメッセージ>, "msg_type": "INNITIAL_CONNECTION", "destination":"指定されたサーバー名", "map_id":所属しているマップのID, "ip_address": 自身のIPアドレス(指定されたサーバーアドレスと同じサブネット, "building_number": 0, "floor_level":0 }
後述の「ファイルの送信方法」セクションを参照してください。
後述の「ファイルの送信方法」セクションを参照してください。
ロボット側は上記のコマンドを送った時点で、次の命令が来るまで待機します。
下記のベースメッセージはすべてのメッセージにつけられます。msg_type毎にそれぞれ異なる要素が追加されます。
sender: サーバー名(ロボットに指定したサーバー名と同一のもの)
duration: 120
command_id: 0
msgtype: メッセージタイプ
ここでは簡単のため、<ベースメッセージ>は上記のうち常に同一のものを指します。
{sender: サーバー名(ロボットに指定したサーバー名と同一のもの)},
{duration: 120},
{command_id: 0}
{"navigation": {<ベースメッセージ>, "msg_type": ナビゲーションタイプ, "x": float, "y": float, "yaw": float}}
ナビゲーションタイプ一覧
*このときのみ以下のフォーマット
{"navigation": {<ベースメッセージ>, "msg_type": FOLLOW_PATH, points: [{x: float, y: float, z: float, yaw: float}, {x: float, y: float, z: float, yaw: float}, ...]}}
{"cmd_vel": {<ベースメッセージ>, "msg_type": CMD_VEL, "linear_x": float, "linear_y": float, "angular_z": float, "linear_z": float}}
ロボットを遠隔から操作するときに使います。
{"graph": {<ベースメッセージ>, "msg_type": "graph", "type": グラフタイプ, /* 各グラフタイプに依存 */}}
グラフタイプ一覧:
{"graph": { <ベースメッセージ>,"msg_type": "graph", "type": "initial_node", "id": int}}
init poseを送る代わりに指定されたノードの座標をinit poseとして送ることができます。
{"graph": {<ベースメッセージ>, "msg_type": "graph", "type": "keystroke", "keystroke": string}}
特定のkeystrokeを送ることで以下のことができます。
{"graph": {<ベースメッセージ>, "msg_type": "graph", "type": "floor_info", "map_id": string, "building_number": int, "floor_level": int}}
現在のグラフの情報とマップをセーブして、フロアの切り替えを行う。ナビゲーション中にこの場所にたどり着いた場合、マップとグラフの切り替えを行う。
{"graph": {<ベースメッセージ>, "msg_type": "graph", "type": "goal", "id": int}}
現在表示されているグラフの中でidで指定されたポイントに向かう。
{"rosbag": {<ベースメッセージ>, "msg_type": "rosbag", "type": rosbagのタイプ, /* タイプに依存 */}}
rosbagタイプ一覧
{"rosbag": {<ベースメッセージ>, "msg_type": "rosbag", "type": "record_start"}}
全トピックをレコード開始
{"rosbag": {<ベースメッセージ>, "msg_type": "rosbag", "type": "record_selected", "topics": topicName1 topicName2 ...}}
指定されたトピックのみをレコード開始
{"rosbag": {<ベースメッセージ>, "msg_type": "rosbag", "type": "play", "title": rosbag title}}
指定されたロスバグタイトルを開始
{"rosbag": {<ベースメッセージ>, "msg_type": "rosbag", "type": "pause"}}
プレイ中のロスバグを一時停止
{"rosbag": {<ベースメッセージ>, "msg_type": "rosbag", "type": "record_stop"}}
プレイ中のロスバグを終了
{"rosbag": {<ベースメッセージ>, "msg_type": "rosbag", "type": "resume"}}
一時停止中の中のロスバグを再開
{"rosbag": {<ベースメッセージ>, "msg_type": "rosbag", "type": "change_speed", "speed": int}}
プレイ中のロスバグのプレイスピードを変更
{"rosbag": {<ベースメッセージ>, "msg_type": "rosbag", "type": "get_rosbags"}}
ロボット本体にあるロスバグのタイトルを取得
{"picture": {<ベースメッセージ>, "msg_type": "picture", "type": pictureのタイプ, /* タイプに依存 */}}
pictureタイプ一覧
{"picture": {<ベースメッセージ>, "msg_type": "picture", "type": "get_all"}}
現在のマップIDに紐づくロボット本体に保存されている写真を取得
{"picture": {<ベースメッセージ>, "msg_type": "picture", "type": "selected", "date": YYYYMMDD}}
ロボット本体に保存されている現在のマップIDの指定された日付の写真を取得
{"process": {<ベースメッセージ>, "msg_type": "process", "systemctl": プロセスタイプ}}
プロセスタイプ:
Navigationに必要なプロセスを立ち上げる
Make Mapに必要なプロセスを立ち上げる
全てのプロセスを終了させる
ロボットとの疎通確認を行う。
(Map作成中のみ)現在のマップをセーブする
保存された3次元マップデータ(pcd)をjson, png, yaml形式に変換する
保存されたマップデータ(json, png, yaml)を取得する
スケジュールリストの中で一番先頭にあるスケジュールを実行する
HalnaPCを再起動する
ロボットはサーバーから受信した各種メッセージに対して、適切な応答や動作を行います。以下では、各メッセージタイプに対するロボットの応答内容と、その際に送信されるJSON形式のレスポンスメッセージを説明します。
レスポンスメッセージ形式:
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": "NAVIGATION_RESPONSE",
"destination": "サーバー名",
"command_id": "受信したcommand_id",
"result": TrueまたはFalse
}
※INITPOSEに対する個別のレスポンスはありません。処理が完了すると状態が更新されます。
※QUITに対する個別のレスポンスはありません。処理が完了すると状態が更新されます。
レスポンスメッセージ形式:
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": "FOLLOW_PATH_RESPONSE",
"destination": "サーバー名",
"command_id": "受信したcommand_id",
"result": TrueまたはFalse
}
ロボットは速度指令を受け取り、即座に移動を開始します。cmd_velメッセージに対する個別の応答メッセージは送信されません。
※initial_nodeに対する個別のレスポンスはありません。
※keystrokeに対する個別のレスポンスはありません。
レスポンスメッセージ形式:
// 成功時
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": "MESSAGE",
"destination": "サーバー名",
"command_id": "0",
"msg": "Change the floor to [building_number]_[floor_level]",
"error": False
}
レスポンスメッセージ形式:
// 成功時
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": "MESSAGE",
"destination": "サーバー名",
"command_id": "0",
"msg": "Published goal with node_name: [id]",
"error": False
}
rosbag操作に対する個別のレスポンスはありません。ただし、"get_rosbags"に対しては、利用可能なバッグファイルの一覧を送信します。
レスポンスメッセージ形式(get_rosbagsの場合):
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": "ROSBAG",
"destination": "サーバー名",
"command_id": "0",
"type": "rosbag_name_list",
"msg": [バッグファイル名のリスト]
}
画像データの送信が完了すると、結果を通知します。
レスポンスメッセージ形式(例):
// 成功時
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": "MESSAGE",
"destination": "サーバー名",
"command_id": "0",
"msg": "Received all the patrol pictures",
"error": False
}
プロセスの開始・停止が完了すると、結果を通知します。
レスポンスメッセージ形式(例: get_mapの場合):
// 成功時
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": "MESSAGE",
"destination": "サーバー名",
"command_id": "0",
"msg": "Received map files",
"error": False
}
指定されたコマンドの実行結果を通知します。
レスポンスメッセージ形式:
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": "RESPONSE",
"destination": "サーバー名",
"command_id": "受信したcommand_id",
"result": TrueまたはFalse
}
メッセージの処理中にエラーが発生した場合、ロボットはエラーメッセージと共に処理結果をサーバーに通知します。
エラーメッセージ形式:
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": "MESSAGE",
"destination": "サーバー名",
"command_id": "0",
"msg": "エラー内容の説明",
"error": True
}
ロボットはサーバーに対して、マップデータ、グラフデータ、画像データ、パラメータデータなどのファイルや情報を送信することができます。これらの送信にはWebSocketのバイナリメッセージまたはテキストメッセージを使用し、特定のヘッダー情報を付加して送信します。サーバー側では、このヘッダー情報を解析してデータを適切にデコード・保存します。
すべてのファイルやデータ送信は、共通の形式を使用して行われます。メッセージの構造は以下の通りです。
// メッセージ全体の構造(バイナリメッセージの場合)
[ヘッダー (バイト列)] + '\0' + [追加情報 (バイト列)] + '\0' + [データ (バイト列)]
// メッセージ全体の構造(テキストメッセージの場合)
{
"sender": "ロボット名",
"timestamp": "現在時刻",
"msgtype": メッセージタイプ,
"destination": "サーバー名",
"command_id": "0",
"type": データタイプ,
"msg": データ(JSON形式)
}
各部分の詳細:
ヘッダーは以下の形式で構成されます。
[type]:[name]
例:
graph_data:original_graph_node.txt
map_data:GlobalMap.png
picture_data:20230101
graph_data
map_data
picture_data
ロボットがグラフデータ(ノード情報やエッジ情報)をサーバーに送信する場合、以下のようにメッセージを構築します。
// ヘッダーの作成
header = "graph_data:original_graph_node.txt"
// エンコード
header_encoded = header.encode('utf-8')
// マップ名とフロア名をエンコード
map_name_encoded = map_name.encode('utf-8')
floor_name_encoded = floor_name.encode('utf-8')
// ファイルデータの読み込み
with open(file_path, 'rb') as file:
file_data = file.read()
// メッセージの組み立て
message = header_encoded + b'\0' + map_name_encoded + b'\0' + floor_name_encoded + b'\0' + file_data
// メッセージの送信
ws.send(message, opcode=websocket.ABNF.OPCODE_BINARY)
マップデータを送信する場合も、同様の形式を使用します。
// ヘッダーの作成
header = "map_data:GlobalMap.png"
// エンコード
header_encoded = header.encode('utf-8')
// マップ名とフロア名をエンコード
map_name_encoded = map_name.encode('utf-8')
floor_name_encoded = floor_name.encode('utf-8')
// ファイルデータの読み込み
with open(map_file_path, 'rb') as file:
map_data = file.read()
// メッセージの組み立て
message = header_encoded + b'\0' + map_name_encoded + b'\0' + floor_name_encoded + b'\0' + map_data
// メッセージの送信
ws.send(message, opcode=websocket.ABNF.OPCODE_BINARY)
ロボットが撮影した画像データを送信する場合も、同様の形式を使用します。
// ヘッダーの作成
header = "picture_data:20230101"
// エンコード
header_encoded = header.encode('utf-8')
// マップ名とファイル名をエンコード
map_name_encoded = map_name.encode('utf-8')
file_name_encoded = image_file_name.encode('utf-8')
// 画像データの読み込み
with open(image_file_path, 'rb') as file:
image_data = file.read()
// メッセージの組み立て
message = header_encoded + b'\0' + map_name_encoded + b'\0' + file_name_encoded + b'\0' + image_data
// メッセージの送信
ws.send(message, opcode=websocket.ABNF.OPCODE_BINARY)
サーバーは受信したバイナリメッセージを以下の手順でデコードします。
# 受信したバイナリデータを分割
sections = message.split(b'\0')
# ヘッダーのデコード
header = sections[0].decode('utf-8')
type_, name = header.split(':')
additional_info = sections[1].decode('utf-8')
data = sections[2] # データ部分
# ファイルの保存先を決定
save_path = determine_save_path(type_, name, additional_info)
# ファイルを保存
with open(save_path, 'wb') as file:
file.write(data)
マップデータにはPNGファイル、YAMLファイル、JSONファイルなどが含まれます。これらはマップ名とフロア名に基づいて適切なディレクトリに保存します。
グラフデータはノード情報とエッジ情報のテキストファイルです。マップ名とフロア名に基づいて保存します。
画像データはロボットが撮影した画像ファイルです。日付やマップ名に基づいて保存します。ファイル名や日付情報はヘッダーや追加情報から取得します。
パラメータデータはロボットの設定情報を含むJSON形式のデータです。サーバー側でパースして、必要に応じて設定を更新します。
{
<ベースメッセージ>,
"msg_type": TELEMETRY,
"x": float,
"y": float,
"z": float,
"yaw": float,
"battery_level": float,
"status": int,
"linear_vel_x": float,
"linear_vel_y": float,
"angular_vel": float,
"occupied_cells": [{"x": float, "y": float}, {"x": float, "y": float}, ...],
"graph_nodes": graph_nodes, *
"graph_edges": graph_edges, *
"building_number": int,
"floor_level": int
}
*graph_nodes/graph_edgesは以下のフォーマット(グラフの情報は、現在のマップに紐づいているグラフ情報を送っています。)
[
{
"id": int,
"x": float,
"y": float,
"z": float,
"yaw": float,
"node_attribute": int,
"node_state_1": float,
"node_state_2": float,
"node_state_3": float
},
{
"id": int,
"x": float,
"y": float,
"z": float,
"yaw": float,
"node_attribute": int,
"node_state_1": float,
"node_state_2": float,
"node_state_3": float
},
...
]
[
{
"id": int,
"point_a":{
"x": float,
"y": float,
"z": float
},
"point_b":{
"x": float,
"y": float,
"z": float
},
"way_to_walk": int,
"robot_speed": float,
"edge_state": int,
"edge_state_1":float,
"edge_state_2":float,
"edge_state_3":float,
"edge_state_4":float,
},
{
"id": int,
"point_a":{
"x": float,
"y": float,
"z": float
},
"point_b":{
"x": float,
"y": float,
"z": float
},
"way_to_walk": int,
"robot_speed": float,
"edge_state": int,
"edge_state_1":float,
"edge_state_2":float,
"edge_state_3":float,
"edge_state_4":float,
},
...
]
ロボットは内部にネットワーク設定やパラメータ情報、グラフの編集、そして巡回経路設定を行えるサーバーを立てています。
アクセス方法は http://robotのIPアドレス:8000 です。
以下がアクセスした先のポータル画面です。