1. はじめに
先日、Open-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で、オフィスビルにおける簡単な館内配送シミュレーションをしてみた[1]とOpen-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で、オフィスビルにおける簡単な館内配送シミュレーションをしてみた その2 時間帯別荷物搬入個数の配送への反映[2]にて濱野ら[3]の論文を参考に、オフィスビルにおける館内配送を対象にシミュレーションをしてみました。
これらの記事で実施してきたシミュレーションでは、エレベータとの連携や荷物の搬入時間について反映してきましたが、荷物のサイズは考慮にいれていませんでした。世の中にある搬送ロボットは、搬送容量が多種多様であり、小さいものを運べるロボットから大きなものまで運べるロボットまで様々です。
そこでこの記事では荷物のサイズによって搬送するロボットを分けた場合のシミュレーションを行い、配送時間などに影響がでるのかをシミュレーションしてみたいと思います。
結論を言いますと、色々とシミュレーション条件を設定はしていったのですが、5章に示すようにロボットが動かなくなり、シミュレーションを完遂できませんでした。
2. 実行環境
CPU: CORE i7 7th Gen
メモリ: 32GB
GPU: GeForce RTX 2070
OS: Ubuntu22.04(WSL2ではなくPCに直接インストール)
ROS2: Humble
3. シミュレーション条件
本記事では、シミュレーションする建物モデル、配送先、館内配送開始位置、ロボット走行ルートについては参考記事[1]の条件と同じとします。
3.1 使用するロボットの種類と台数について
使用するロボットモデルは以下の図に示すtinyRobotとdeliveryRobotそれぞれ1台とします。図中の左側がtinyRobotで、図中の右側のロボットがdeliveryRobotです。それぞれOpenRMFのデフォルト環境で用意されているロボットです。
3.2 搬入される荷物のサイズについて
参考文献[3]では搬入される荷物のサイズについての言及はありますが、その割合までの記載は私が読む限りではありませんでした。参考記事[3]で述べれられている荷物のサイズは大中小とありますので、この記事ではとりあえずそれぞれのサイズが1/3づつ搬入されてくるものとします。そして小サイズと中サイズはtinyRobotで、大サイズはdeliveryRobotで運ぶものとします。
3.3 シミュレーション条件のまとめ
ここまでの項で設定した項目を以下の表に一旦まとめます。
項目 | 内容 |
---|---|
ロボット発進位置 | 館内メールセンター(地上3階) |
配送場所① | 地上3階~地上18階のそれぞれのフロアのオフィスエリアに各2か所(上図で示した配送先1と配送先2) |
配送場所② | 地上19階の厨房に1か所 |
配送場所③ | 地上19階のコンビニに1か所 |
館内配送の頻度 | 午前10時開始配送:21個(小・中サイズの荷物は14個 大サイズは7個) |
午前10時開始配送の詳細(本記事のシミュレーション対象) | 地上3階~地上18階の「配送先1」(位置は上図参照)に各1個:計16個、地上19階のコンビニ:3個 地上19階の厨房:2個 |
ロボット配送方法 | 1配送につき1個の荷物を配送する。そしてその荷物は配送先に到着したら荷物は即受け取られるとする。そして受け取られたらすぐにロボットは発進元である館内メールセンターに帰還し、次の配送物がある場合は館内メールセンター帰還後にすぐに「ロボット巡回開始位置」より配送先に発進する |
ロボット種類 | tinyRobot(小・中サイズ荷物用)、deliveryRobot(大サイズ荷物用) |
ロボット台数 | 2台(tinyRobot:1台、deliveryRobot:1台) |
ロボットが使用可能なエレベータ | 1台 |
4. シミュレーション用のプログラム
シミュレーションの設定、タスクの指示方法、ロボットの現在位置やタスクステータスの取得方法は参考文献[1]と同様の手法を採用しました。そのため、本稿ではそれらの詳細説明は省略させていただきます。
そしてタスク指示用のjsonファイルについて、delivaryRobotが運ぶ大サイズの荷物は19階にあるコンビニと厨房向けに5個、3階と4階向けにそれぞれ1個ずつ、合計7個で設定しました。
この設定の根拠として、コンビニや厨房への納入物は一般的に大容量のものが多いと想定されることが挙げられます。また、オフィスビルの低層階には倉庫が設置されていることが多く、そこにも大型の荷物が送られる可能性が高いと考えました。これらの想定は個人的な経験や観察に基づいていますので、あまり厳密ではありませんのでご了承ください。
以下にロボットに与えるタスクをまとめたJSONと、そのJSONを読み込んでロボットに指示を与えるPythonコードを示します。
[
{
"places": ["start_point", "L19_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "deliveryRobot"
},
{
"places": ["start_point", "L5_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L4_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "deliveryRobot"
},
{
"places": ["start_point", "L6_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L3_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "deliveryRobot"
},
{
"places": ["start_point", "L7_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L19_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "deliveryRobot"
},
{
"places": ["start_point", "L8_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L19_B"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "deliveryRobot"
},
{
"places": ["start_point", "L9_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L19_B"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "deliveryRobot"
},
{
"places": ["start_point", "L10_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L11_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L12_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L13_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L14_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L15_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L16_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L17_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L18_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
},
{
"places": ["start_point", "L19_A"],
"rounds": 1,
"use_sim_time": true,
"fleet_name": "tinyRobot"
}
]
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"]),
"--fleet", task["fleet_name"]
])
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.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)
5. シミュレーション結果とまとめ
結論を言いますと、ロボットが以下の図のようにエレベータ前で、互いの進路を妨げてしまい、身動きが取れなくなってしまったことから、シミュレーションを完遂することはできませんでした。
この現象は、1台のロボットが上の階に行こうとエレベータ前で待っている間に、もう1台のロボットがスタート地点に戻ろうとしてエレベータで降りてきてしまった時に発生します。以下にスクショと動画を示しますが、両方のロボットの計画経路が重複してしまい、画面右側にあるdeliveryRobotが動こうとしてもtinyRobotが全く動かないため、進むことも引くこともできなくなっています。
そのため以下の図のようにEVホールに2つの経路を設け何個かholding pointも設けました。(ストップウォッチマークがあるのがholding pointです。)
うまくいけば以下の動画のようにロボットが互いに道を譲りあうこともあるのですが、毎回できるわけではなく発動条件があるようです。そしてこの記事での条件では前述のようにロボット同士が互いの進路を妨げてしまい、身動きが取れなくなってしまうことが毎回起こってしまい、シミュレーションを完遂することはできませんでした。
この対策として以下のことを今は考えており、次回以降の記事で試行した結果を報告しようと思っています。
- tinyRobotとDeliveryRobotの経路を同一のものとせず、別のレイヤーにする
- 使用するエレベータを2つに増やしてみる(コスト増になるので、現実的にあまりやらない対策かもしれませんが、シミュレーションとしては面白いと思ってます)
- エレベータに乗車する経路を現状の1本から2本以上にする(ドアを障害物として検知して、そもそも乗車できなくなる可能性もあると考えています。)
参考文献
[1] Open-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で、オフィスビルにおける簡単な館内配送シミュレーションをしてみた
[2] Open-RMFで複数ロボットとエレベータの連携をシミュレーションできる環境で、オフィスビルにおける簡単な館内配送シミュレーションをしてみた
[3] 濱野百恵,南部世紀夫,小早川悟,田部井裕也: オフィスビルの映像記録を用いた館内貨物量調査の基礎的研究, 日本物流学会誌 第30号, pp.139-145, 2022.