1. はじめに
「WSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる ○○編」という形で今まで何個か記事を書いてきました。
- WSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる 簡単な配送シミュレーションと得られた知見編
- WSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる タスクステータス取得編
- WSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる 人間とtemi出現編
これらの記事はすべてシミュレーションというよりもOpen-RMFの機能を試行したものですので、少し物足りなく感じていました。そこでロボットを用いた配送について、単機ではなく複数のロボットを使った配送を行った場合はどのような効果があるのかということをOpen-RMFの機能を使いつつシミュレーションし、その効果を算出してみようとしたのが、この記事の内容になります。
余談:先日、Isaac Simを試すためにWindows11で構築したWSL2の環境を消してしまいましたので、Ubuntu22.04の環境でOpen-RMFの環境を再構築しました。
2. 実行環境
CPU: CORE i7 7th Gen
メモリ: 32GB
GPU: GeForce RTX 2070
OS: Ubuntu22.04(WSL2ではなくPCに直接インストール)
ROS2: Humble
3. シミュレーション条件
このシミュレーションをするにあたって、実際のオフィスビル内の配送(以下、館内配送)についての調査結果を参考に条件を設定していきたいと思います。この館内配送については濱野ら[1]らの論文を参考にしたいと思います。
3.1 シミュレーションをする建物モデルの設定について
[1]の論文では、総延床面積が50,590$m^2$の地上22階、地下3階、塔屋1階のビルを調査対象にしています。そして用途としてオフィス、駐車場、食堂、コンビニ、その他としてそれぞれの構成比は63.4%、8.7%、4.1%、0.2%、23.7%としています。
この記事ではこの記載から、ひと階につき約1950$m^2$(≒50,590/26)の広さを持つ、以下の構成のオフィスビルがあると設定します。なお、階ごとの広さは同じとします。
用途 | 対象階数 |
---|---|
駐車場 | 地下1階~地下3階 |
その他 | 地上1階~2階 |
オフィス | 地上3階~地上18階 |
食堂(コンビニ含む) | 地上19階 |
その他 | 地上20階~地上22階 塔屋1階 |
そして、今回のシミュレーションの対象としてはオフィスと食堂(コンビニを含む)の地上3階~地上19階までの範囲とします。またオフィスのレイアウトは先ほど設定した1階分の面積(約1950$m^2$)より少し小さくなってしまいますが、以下のサイトの"PLAN A"のレイアウトがちょうどよいので、これを参考に作成したいと思います。
また食堂のレイアウトについては良い例を見つけることができませんでしたので、上記のリンクのオフィスレイアウトにおけるオフィスエリアを食堂、オープンミーティングスペースを厨房、会議室をコンビニとして設定したいと思います。
そして以下がOpenRMFのTraffic Editor[2]で作成した建物モデルをGazebo[3]で表示した様子です。1階と2階部分を除き3階~19階までを作成しました。
そして地上3階~地上18階までの構成は以下のようにしました(次節で述べますが、3階の会議室エリアは若干違います。)。なお、本記事は実空間を再現することが主題ではないため、什器の設置はしていません。
それぞれのスペースや大きさの概要を追記すると以下のようになります。
また19階は以下のような構成にしました。なお、19階についても什器は設置していません。
3.2 館内配送の種類について
[1]の論文では、館内配送については以下の3つの形態があるとしています。
- ①館内配送業者が一括荷受けして各フロア配送
- ②卸売業者等が直接各フロアへ配送
- ③一括受けされた荷物を個人が直接取りに行く
私が勤めているオフィスビルでもほぼ同じような形態をとっていますので、この設定に違和感はありません。そして本記事で対象とするロボットによる館内配送シミュレーションとしては①の館内配送業者による各フロアへの配送を対象としたいと思います。
②の卸売業者が配送するものを除いた理由としては、②の形態で配送されるものは自動販売機の飲料やプリンターへのインク類であるため、ただ配送するだけでなく、配送先での飲料の補給などの作業も必要であると考えられ、配送ロボットによる省力の効果は限定的と考えられるためです。また③の形態については、そもそもロボットによる配送を念頭に置いたものではないと考え除外しました。しかし将来的に③の形態は、自分の代わりにロボットを荷受けの場所まで受け取りに行かせることで館内配送を省力化するということも考えられます。そこについてはfuture workとして本記事のスコープからは外したいと思います。
3.3 館内配送の総量について
①の形態における荷物量としては、[1]の論文では曜日による変動があることが述べられています。そして荷物搬入個数の最大は月曜日と金曜日が最大で41個としていますので、本記事ではその数値をシミュレーションに反映したいと思います。
3.4 館内配送の開始位置について
①の形態において、「館内配送業者が一括荷受け」する場所は[1]の論文では、「館内メールセンター」としています。館内メールセンターの位置はビルによってまちまちだとは思いますが、配送業者さん目線で考えれば、低層階にある方がアクセスがしやすいかと考えられます。そのためこの記事ではシミュレーション環境の最低層階である地上3階の会議室のところに館内メールセンターを設定したいと思います。また配送ロボットもそこから発進するようにします。
3.5 館内配送の頻度について
館内メールセンターからの配送頻度は[1]の論文では、午前・午後で1回ずつとしていますので、本記事では午前10時と午後15時に配送開始と設定します。また[1]の論文では、時間帯による搬入個数については午前の方が午後よりも数倍多いことが示されています。しかし午前中に搬入された荷物をすべて午前に配送してしまうことは考えづらいため、午前・午後でほぼ同じ量を配送するとして午前10時の開始の配送では21個、午後15時開始の配送では20個を配送すると設定して、配送量の多い午前10時開始の配送の方をシミュレーション対象としたいと思います。また荷物の大きさについても、[1]の論文では違いがあることを述べていますが、本記事では後述する配送ロボットで搬送できる大きさという設定にして、荷物大きさの違いを考慮することについてはスコープ外とします。
3.6 ロボット配送方法について
本記事ではロボットによる1配送につき1個の荷物を配送する。そしてその荷物は配送先に到着したら荷物は即受け取られるとする。そして受け取られたらすぐにロボットは発進元である館内メールセンターに帰還し、次の配送物がある場合は館内メールセンター帰還後すぐに配送先に発進するとします。実際の館内配送では同配送先の荷物を同梱して配送することや荷物がすぐに受け取られず配送先で待機することや荷物積み込み作業により館内メールセンターに待機することもあると考えられますが、本記事ではそのような場合をスコープ外とします。
また建物設備との連携については、エレベータ1台と連携して垂直移動することとし、それ以外の設備とは連携しません。
3.7 配送先とそれに紐づいた配送頻度・配送量について
荷物の配送先については各階のオフィスエリアに2か所、地上19階の厨房に1か所、地上19階のコンビニに1か所設定し、荷物の配送については以下のように設定します。
- オフィスエリア:午後と午前でそれぞれ1個配送(午前16個 午後16個 計32個)。またオフィスエリアには2か所配送先を設定しているので午前と午後では別々のところに配送されるものとする。
- 地上19階のコンビニには午前と午後で3個づつの計6個配送する。
- 地上19階の厨房には午前2個、午後1個の計3個配送する。
3.8 配送先と館内配送開始位置の図
ここで地上3階における配送先と館内メールセンター(ロボットの待機場所)の位置を以下の図に示します。図はtraffic-editorで表示したときの様子であり、緑線はロボットが移動する経路を表しており、1台でも複数台でも、ロボットが使用する経路は変わりません。また配送先は図左下に「配送先1」、右端中央当たりに「配送先2」を設定しました。
また館内メールセンターにおけるロボットの待機場所は以下のように設定しました。図は2台のロボットを設置した場合のものになります。またシミュレーションではロボットは待機位置から配送を開始し、各配送先と図中の「ロボット巡回開始位置」を行き来し、すべてのタスクが完了したらまた待機位置に戻るという形になります。
またGazeboで表示した環境において上図の地上3階における館内メールセンターと配送先を示すと以下になります。
次に地上4階~地上18階における配送先の位置をtraffic-editorで表示したときの図を以下に示します。設定している配送先は先ほど示した地上3階における配送先と位置は同じであり、経路も館内メールセンターに至る経路がない以外は同じとしています。
またGazeboで表示した環境において上図の地上4階~地上18階におけると配送先を示すと以下になります。
次に地上19階のレイアウトと配送先の位置をtraffic-editorで表示したときの図を以下に示します。
またGazeboで表示した環境において上図の地上19階におけると配送先を示すと以下になります。
3.9 配送シミュレーションに用いるロボットの種類と台数の設定について
配送シミュレーションに用いるロボットはrmf_demos[4]のOffice Worldなどで配送ロボットとして用いられている"tinyRobot"を用います。各種設定はデフォルトで設定されている値を用います。
台数としては1台の場合と2台の場合の2パターンをシミュレーションします。
3.10 設定のまとめ
ここまでの項で設定した項目を以下の表に一旦まとめます。
項目 | 内容 |
---|---|
ロボット発進位置 | 館内メールセンター(地上3階) |
配送場所① | 地上3階~地上18階のそれぞれのフロアのオフィスエリアに各2か所(上図で示した配送先1と配送先2) |
配送場所② | 地上19階の厨房に1か所 |
配送場所③ | 地上19階のコンビニに1か所 |
館内配送の総量 | 41個 |
館内配送の頻度 | 午前10時開始配送:21個(本記事のシミュレーションン対象)、午後15時開始配送:20個 |
午前10時開始配送の詳細(本記事のシミュレーション対象) | 地上3階~地上18階の「配送先1」(位置は上図参照)に各1個:計16個、地上19階のコンビニ:3個 地上19階の厨房:2個 |
午後15時開始配送の詳細 | 地上3階~地上18階の「配送先2」(位置は上図参照)に各1個:計16個、地上19階のコンビニ:3個 地上19階の厨房:1個 |
ロボット配送方法 | 1配送につき1個の荷物を配送する。そしてその荷物は配送先に到着したら荷物は即受け取られるとする。そして受け取られたらすぐにロボットは発進元である館内メールセンターに帰還し、次の配送物がある場合は館内メールセンター帰還後にすぐに「ロボット巡回開始位置」より配送先に発進する |
ロボット種類 | tinyRobot |
ロボット台数 | 1台 or 2台 の2通りをシミュレーション |
ロボットが使用可能なエレベータ | 1台 |
4. シミュレーション
4.1 ロボットシミュレーションを行うためのOpenRMF側の設定
launchファイルの作成
"~/rmf_ws/src/demonstrations/rmf_demos/rmf_demos/launch"の中に以下の内容のdelivery_test.launch.xmlを作成しました。また本記事では特に使いませんが、dashboard_configのファイルはgithubで提供されているデモのclinicを名前をdelivery_testに変えてそのまま利用しました。
<?xml version='1.0' ?>
<launch>
<arg name="use_sim_time" default="false"/>
<!-- Common launch -->
<include file="$(find-pkg-share rmf_demos)/common.launch.xml">
<arg name="use_sim_time" value="true"/>
<arg name="viz_config_file" value ="$(find-pkg-share rmf_demos)/include/delivery_test/delivery_test.rviz"/>
<arg name="config_file" value="$(find-pkg-share rmf_demos_maps)/delivery_test/delivery_test.building.yaml"/>
<arg name="dashboard_config_file" value="$(find-pkg-share rmf_demos_dashboard_resources)/delivery_test/dashboard_config.json"/>
</include>
<!-- TinyRobot fleet adapter -->
<group>
<include file="$(find-pkg-share rmf_demos_fleet_adapter)/launch/fleet_adapter.launch.xml">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="nav_graph_file" value="$(find-pkg-share rmf_demos_maps)/maps/delivery_test/nav_graphs/0.yaml" />
<arg name="config_file" value="$(find-pkg-share rmf_demos)/config/delivery_test/tinyRobot_config.yaml"/>
</include>
</group>
</launch>
次に"~/rmf_ws/src/demonstrations/rmf_demos/rmf_demos_gz_classic/launch"の中に以下の内容のdelivery_test.launch.xmlを作成しました
<?xml version='1.0' ?>
<launch>
<arg name="gazebo_version" default="11"/>
<arg name="use_sim_time" default="true"/>
<arg name="failover_mode" default="false"/>
<!-- Common launch -->
<include file="$(find-pkg-share rmf_demos)/delivery_test.launch.xml">
<arg name="use_sim_time" value="true"/>
<arg name="failover_mode" value="$(var failover_mode)"/>
</include>
<!-- Simulation launch -->
<include file="$(find-pkg-share rmf_demos_gz_classic)/simulation.launch.xml">
<arg name="map_name" value="delivery_test" />
<arg name="gazebo_version" value="$(var gazebo_version)" />
</include>
</launch>
configファイルの作成
以下の手順を実施しました。
- "~/rmf_ws/src/demonstrations/rmf_demos/rmf_demos/config"の中に"delivery_test"という名前のフォルダを作成。
- 同じフォルダ内にある"config/clinic"の中にある"tinyRobot_config.yaml"を"delivery_test"の中にコピー。
注: このyamlファイルではそれぞれのtinyRobotの充電スポットの名前を"tinyRobot_1_charger"、"tinyRobot_2_charger"としていますのでtraffic-editorで設定する充電スポットの名前もそれに合わせる必要があります。
rvizファイルの作成
以下の手順を実施しました。
- "~/rmf_ws/src/demonstrations/rmf_demos/rmf_demos/launch/include"の中に"delivery_test"という名前のフォルダを作成。
- 同じフォルダ内にある"include/clinic"の中にある"clinic.rviz"を"delivery_test.rviz"として"delivery_test"の中にコピー。
4.2 ビルド
上記の設定が終わったら以下のコマンドでビルドをします。
cd ~/rmf_ws
source /opt/ros/humble/setup.bash
export CXX=clang++
export CC=clang
colcon build
4.3 シミュレーション環境の起動
以下のコマンドでGazeboとrvizを起動します。
cd ~/rmf_ws
source ~/rmf_ws/install/setup.bash
ros2 launch rmf_demos_gz delivery_test.launch.xml server_uri:="ws://localhost:7878"
4.4 館内配送シミュレーションでの配送指示方法
[4]で解説されているRMF Panelの"Submit a List of Tasks"からjson形式でタスクを一気に出そうと思ったのですが、受け入れられるタスクの数には限りがあるみたいでしたので、以下のコードで実行中及び待機中のタスクが合わせて最大4つになるように制御しつつシミュレーションをしました。なお、私の環境ではタスクが完了しても完了率が100%にならず完了率99%になってしまいます。そのため完了率が99%に達したらタスクは完了したとして次のタスクを出すようにしています。そして無理やり感がありますが、subprocessを使ってros2のコマンドを打ってタスクを出す形をとりました。
import subprocess
import json
import requests
import schedule
import time
tasks = []
current_index = 0
url = "http://localhost:8083/task_list" # タスクの進行状況を取得するAPIエンドポイント
def run_dispatch_patrol(task):
command = [
"ros2", "run", "rmf_demos_tasks", "dispatch_patrol",
"-p"
]
command.extend(task["places"])
command.extend([
"-n", str(task["rounds"])
])
if task.get("use_sim_time", False):
command.append("--use_sim_time")
result = subprocess.run(command, capture_output=True, text=True)
if result.returncode == 0:
print("コマンドが成功しました:", result.stdout)
else:
print("コマンドの実行に失敗しました:", result.stderr)
def load_tasks_and_run():
global tasks
with open('tasks_am.json', 'r') as file:
tasks = json.load(file)
# 最初に4つのタスクを発行
for task in tasks[:4]:
run_dispatch_patrol(task)
global current_index
current_index += 1 # 発行したタスク数をカウント
# 定期的なタスク監視と発行の開始
schedule.every(1).minutes.do(check_and_dispatch_tasks)
def check_and_dispatch_tasks():
global current_index, active_task_count
# APIからタスクの進行状況を取得し、アクティブなタスクの数を数える
active_task_count = 0
response = requests.get(url)
current_tasks = response.json()
for task in current_tasks:
progress = float(task['progress'].replace('%', '')) # パーセンテージ記号を取り除いて数値に変換
if progress < 99:
active_task_count += 1
# アクティブなタスクが4未満の場合に新たなタスクを投げる
while active_task_count < 4 and current_index < len(tasks):
run_dispatch_patrol(tasks[current_index])
active_task_count += 1
current_index += 1
if __name__ == '__main__':
load_tasks_and_run()
while True:
schedule.run_pending()
time.sleep(1)
またタスクはdeliveryではなくpatrolとして出しました。これはWSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる 簡単な配送シミュレーションと得られた知見編[5]にて、私の環境ではdeliveryタスクでは2回目以降の配送が失敗してしまうことへの対策です。また今回のシミュレーション条件でも「荷物は配送先に到着したら荷物は即受け取られ、すぐにロボットの発進元である館内メールセンターに帰還して、次の配送物があれば帰還後にすぐに発進する」としておりますので、patorolタスクでも同じ動きを再現できると考えたこともあります。
なお、上記のコードで読み込んでいるtask_am.jsonの内容は以下です。「ロボット巡回開始位置」は"start_point"、「配送先1」は"階数_A"、コンビニは"L19_A"、厨房は"L19_B"と設定しています。
[
{
"places": ["start_point", "L3_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L4_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L5_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L6_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L7_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L8_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L9_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L10_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L11_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L12_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L13_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L14_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L15_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L16_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L17_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L18_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L19_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L19_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L19_A"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L19_B"],
"rounds": 1,
"use_sim_time": true
},
{
"places": ["start_point", "L19_B"],
"rounds": 1,
"use_sim_time": true
}
]
4.5 館内配送シミュレーションでのロボット現在地とタスクステータスの取得方法
シミュレーション開始と同時に、WSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる 軌跡プロット編[6]で紹介しているget_tinyRobot_position.pyとWSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる タスクステータス取得編[7]のget_tinyRobot_taskstatus.pyプログラムを実行しロボットの現在地とタスクの状態をcsvで保存していきます。
5.結果
5.1 ロボットが1台の時の結果
ロボットを1台用いた時のシミュレーションの時系列を以下に示します。
結果として配送開始から完了まで2.6時間かかっています。
項目 | シミュレーション開始からの経過時間 |
---|---|
配送開始 | 55.42秒 |
3階(L3_A)への配送完了 | 211.48秒 |
4階(L4_A)への配送完了 | 574.67秒 |
5階(L5_A)への配送完了 | 1033.21秒 |
6階(L6_A)への配送完了 | 1502.63秒 |
7階(L7_A)への配送完了 | 1973.99秒 |
8階(L8_A)への配送完了 | 2444.49秒 |
9階(L9_A)への配送完了 | 2922.84秒 |
12階(L12_A)への配送完了 | 3400.34秒 |
13階(L13_A)への配送完了 | 3883.91秒 |
10階(L10_A)への配送完了 | 4363.31秒 |
15階(L15_A)への配送完了 | 4845.78秒 |
16階(L16_A)への配送完了 | 5339.27秒 |
17階(L17_A)への配送完了 | 5834.75秒 |
18階(L18_A)への配送完了 | 6332.21秒 |
19階コンビニへ(L19_A)の配送1回目完了 | 6787.13秒 |
19階コンビニへ(L19_A)の配送2回目完了 | 7195.36秒 |
19階コンビニへ(L19_A)の配送3回目完了 | 7601.68秒 |
19階厨房(L19_B)への配送1回目完了 | 8039.12秒 |
19階厨房(L19_B)への配送2回目完了 | 8510.63秒 |
14階(L14_A)への配送完了 | 8993.48秒 |
11階(L11_A)への配送完了 | 9482.5秒 |
5.2 ロボットが2台の時の結果
ロボットを2台用いた時のシミュレーションの時系列を以下に示します。ロボットの名前はそれぞれtinyRobot_1とtinyRobot_2としています。
結果として配送開始から完了まで1.5時間かかっています。
項目 | シミュレーション開始からの経過時間 | 配送したロボット |
---|---|---|
tinyRobot_2の配送開始 | 132.56秒 | --- |
tinyRobot_1の配送開始 | 134.75秒 | --- |
3階(L3_A)への配送完了 | 288.23秒 | tinyRobot_2 |
4階(L4_A)への配送完了 | 411.37秒 | tinyRobot_1 |
6階(L6_A)への配送完了 | 663.48秒 | tinyRobot_2 |
7階(L7_A)への配送完了 | 888.87秒 | tinyRobot_1 |
8階(L8_A)への配送完了 | 1141.91秒 | tinyRobot_2 |
9階(L9_A)への配送完了 | 1374.89秒 | tinyRobot_1 |
5階(L5_A)への配送完了 | 1618.36秒 | tinyRobot_2 |
10階(L10_A)への配送完了 | 1866.82秒 | tinyRobot_1 |
12階(L12_A)への配送完了 | 2109.81秒 | tinyRobot_2 |
13階(L13_A)への配送完了 | 2359.36秒 | tinyRobot_1 |
14階(L14_A)への配送完了 | 2614.34秒 | tinyRobot_2 |
11階(L11_A)への配送完了 | 2862.85秒 | tinyRobot_1 |
17階(L17_A)への配送完了 | 3124.24秒 | tinyRobot_2 |
16階(L16_A)への配送完了 | 3386.29秒 | tinyRobot_1 |
18階(L18_A)への配送完了 | 3650.85秒 | tinyRobot_2 |
19階コンビニへ(L19_A)の配送1回目完了 | 3868.79秒 | tinyRobot_1 |
19階コンビニへ(L19_A)の配送2回目完了 | 4284.18秒 | tinyRobot_2 |
19階コンビニへ(L19_A)の配送3回目完了 | 4377.89秒 | tinyRobot_1 |
15階(L15_A)への配送完了 | 4889.82秒 | tinyRobot_2 |
19階厨房(L19_B)への配送1回目完了 | 4962.48秒 | tinyRobot_1 |
19階厨房(L19_B)への配送2回目完了 | 5466.02秒 | tinyRobot_2 |
6. まとめ
本記事ではロボットを用いた配送について、単機ではなく複数台のロボットを使った館内配送を行った場合はどのような効果があるのかということをOpen-RMFの機能を使いつつシミュレーションし、その効果を算出するということを目的に[1]を参考に条件を設定および環境を構築してシミュレーションをしました。そして、ロボット単機で館内配送をした場合に2.6時間かかる配送はロボットを2台にすることで約1時間ほど短縮できる(配送時間:1.5時間)ことを確認できました。ロボットを2台にすることで2倍の短縮効果があるわけではなかった理由としてはエレベータ利用について待ち時間が発生したとことや衝突を回避するために片方のロボットがどこかで待機していた時間があったためと考えられます。ロボット位置の時系列データは抽出できていますので、次回以降このことについての分析をしてみたいと思います。
またロボット単機での配送には2.6時間かかるということで10時配送開始とすると13時近くまでかかるということになります。実際のオフィスでは12時に昼休みが始まり人によるエレベータの利用が増えると考えられますので、ロボットの移動にはかなりの制限がかかります。そのため単機での配送は今回シミュレーションした時間よりも、もっと長い時間がかかる考えられます。また今回は什器の配置や人の動きによる外乱を加えておらず、ロボット配送には「理想的な状態」でのシミュレーションでした。そのため複数台用いた場合でも実際はもっと長い時間が配送にはかかると考えられます。なお、Open-RMFには人の動きを外乱として再現する機能もあるようですので、次回以降はこの機能の導入や什器の配置もしていきたいと考えています。
参考文献
[1] 濱野百恵,南部世紀夫,小早川悟,田部井裕也: オフィスビルの映像記録を用いた館内貨物量調査の基礎的研究, 日本物流学会誌 第30号, pp.139-145, 2022.
[2]Traffic Editor
[3]Gazebo
[4]rmf_demos
[5]WSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる 簡単な配送シミュレーションと得られた知見編
[6]WSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる 軌跡プロット編
[7]WSL2環境下で構築したOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で遊んでみる タスクステータス取得編