LoginSignup
11
7

実験用AGVの作成 - (1) - Simulatorを使った機構の検討

Last updated at Posted at 2023-03-23

はじめに

自律移動ソフトの開発を行うにあたって「適当な台車がない!」という問題にぶつかる方は多いと思います。
市販の台車を使うと次のような課題が出てきます。

  • turtlebot等の台車だと車輪や筐体が小さくて、少しでも路面が凸凹していると走れない
  • 少し大きめの機材を乗せることができない
  • 試作開発ベースに運用車両を開発する時、市販の台車だと駆動部品などを使うことができない

これらの課題を解決するために自前の台車を作ろうと考えました。ただ、自前台車を作っただけでは開発コストが大きくなり「買った方がいい」という事になってしまいます。作成する車両の検討情報を公開・共有することで、研究用途の台車作成が少しでも手軽にできるようになればと思いこの投稿を行いました。

シミュレータを使った台車構造の検討、台車設計、台車製造、モータードライバ開発、自律移動モジュール開発と複数回に分けて投稿していく予定です。

今回は台車構造の検討(前編)です。実機を作っての試行錯誤ではなく、シミュレータでの試行錯誤のヒントになればいいなと思います。

環境

下記の内容で動作しています。

項目
CPU Core i7-8700K
Ubuntu 18.04
ROS Melodic
Gazebo 9.0.0

Gazebo Simulator

ロボットの構造検討はROS開発ではおなじみのGazebo Simulatorを用います。車輪の取付構造について事前にシミュレーションで確認しておきます。バージョンアップしたようですが今回は古い方を使いました。

シミュレータを用いた課題の確認

台車は一般的な差動二輪制御型の台車にすることは決めています。そして、台車の特性を素直にするために旋回中心(base_link)を台車の中心に置きたいと考えています。旋回中心が台車の前方や後方にあると旋回時に頭やお尻を振ったようになり安定しません。

また、回転中心が車両中心にあると、その場回転した時の衝突範囲が最も小さくなり、狭いところでの取り回しが有利です。

fig1.png

一方、旋回中心を車両の中心にするため、駆動輪を車両の中心に設置すると補助輪の置き方が課題になります。補助輪は小型の車両であれば、前後に1つずつ置くことが多いです。

fig2.png

この場合、台車のサイズが大きくなると左右に不安定となるため、対策として前後四隅に補助輪を取り付けます。

fig3.png

これで台車は安定しました。しかし、この補助輪の位置では路面状態によっては駆動輪にトラクションがかからず走行できなくなります。下図のように段差やスロープのところで駆動輪が浮いた状態になり、トラクションがかかりません。

fig4.png

車輪接地状態のシミュレーション

gazeboを使ってをシミュレーションしました。2cmの段差とスロープを配置して台車で乗り越えてみます。

sim1.gif

gzeboの[View]メニューからWireframeとContactsにチェックを入れると接地状況と接地圧が可視化されます。スロープに差し掛かったところで駆動輪の接地圧が無くなりトラクションがかからないことが確認できます。また、段差についても前輪の直径が小さいため乗り越えることができません。

シミュレーションデータ

上記シミュレーション用のURDFは次のgithubに公開しています。

実行は下記のように行います。

$ mkdir -p catkin_ws/src
$ cd catkin_ws/src
$ git clone https://github.com/Panasonic-Advanced-Technology/agv_eval_description.git
$ cd ..
$ source /opt/ros/melodic/setup.bash
$ catkin build
$ source devel/setup.bash
$ roslaunch agv_eval_description gazebo.launch sample:=sample1

緩衝キャスターによる段差乗り上げの検討

前輪キャスター径が小さいため2cm程度の段差でも乗り越えることができませんでした。車輪にサスペンション機構を設けることで段差を吸収して乗り越えるようにしてみます。下記のような緩衝キャスターに目をつけていたのでコレを取り付けた場合の状態をシミュレーションします。

caster.pngシシク製 緩衝キャスター

シミュレーションのURDFはsample2です。

$ roslaunch agv_eval_description gazebo.launch sample:=sample2

キャスター部のサスペンションはrevoluteタイプのjointにダンピングとばね定数を設定します。

sample2/caster/caster.urdf.xacro
<joint name="${prefix}_sus_joint" type="revolute">
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <parent link="${prefix}_swing_link"/>
    <child link="${prefix}_sus_link"/>
    <axis xyz="0 1 0"/>
    <limit lower="0.0" upper="0.5" effort="0" velocity="0"/>
    <dynamics damping="0.7"/>
</joint>

joint属性のdynamicsにdampingを設定してスプリングが跳ねることを防ぎます。

sample2/caster/caster.urdf.xacro
<gazebo reference="${prefix}_sus_joint">
    <implicitSpringDamper>true</implicitSpringDamper>
    <springStiffness>45</springStiffness>
    <springReference>0.0</springReference>
</gazebo>

ばね定数は45N/mを設定しました。シミュレーション結果は次の通り。

sim2.gif

残念。やはりスロープは登ることができませんでした。段差については少し勢いがあれば、キャスターのサスペンション部分が効いて乗り越えられるようになりました。しかし、乗り越えた後に駆動輪が浮く状態は変わらないのでそこから先に進むことができません。

駆動輪にトラクションがかからない件についてはまだ対策が必要です。
次回、このあたりの検討とシミュレーションを行います。

おわりに

段差やスロープを乗り越えるためには、足回りの緩衝機構をもうひと工夫する必要があります。6輪車だとロッカー・ボギー機構がありますが複雑になってしまいますのでもう少し簡単な物を考えます。

Next

11
7
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
11
7