はじめに
AGVの実験に使用する台車を作ろうと思い、前回はシミュレータを使って車輪構造の検討を行いました。
前回の検討では緩衝キャスターを用いることで少しの段差を乗り越えることはできましたが、駆動輪が浮いてしまうような段差やスロープでは走行不可能になる課題がわかりました。
今回は台車構造の検討(後編)です。車輪部分の機構をもう少し検討し、段差・スロープの走行性を高めることを検討します。
環境
下記の内容で動作しています。
項目 | 値 |
---|---|
CPU | Core i7-8700K |
Ubuntu | 18.04 |
ROS | Melodic |
Gazebo | 9.0.0 |
ロッカー・ボギー
ロッカー・ボギー機構はNASAが火星探査機向けに開発したサスペンション機構です。6つの駆動輪とそれらを接続するリンケージから構成されます。車輪は地面の起伏に追従しつつ、車体をなるべく水平に保つようになっています。
ただ、これをAGVに適用すると
- 機構が複雑
- 車体を水平に保つためのアクチュエータが必要
- 耐荷重を上げるのが難しそう
という課題が有ると思いました。
工場などで用いるAGVではそれほどの起伏は無いのでもう少し簡単でコストダウンできる機構を考えてみました。
駆動輪にサスペンションを設ける
段差やスロープ乗り上げ時に前輪が持ち上げられると中央の駆動輪が浮いてしまうことが課題です。
回避策としては駆動輪にストロークのあるサスペンションを設けて駆動輪を床面に押し付ける方法も考えられます。
この場合、スロープ侵入時に駆動輪は押し下げられて接地状態を保ちます。
具合は良さそうなのですが作るのが大変。。。
- ちょうどよい強さのバネは何を選択すれば良い?
→ バネが弱いと床面への押し付けが弱くてトラクションがかからない - モーターはどのように取り付ける?
モーターごとストロークさせるか、軸を自在継手で接続する?
→ どちらも機構が大きくなって台車が大きくなりそう
左右独立のボギーアームにする
ロッカー・ボギー機構は片側3つの車輪を全てリンクさせていますが、走破性を犠牲にするなら2つの車輪をリンクするだけで良いのでは?と思いました。
スロープに差し掛かったときはこんな感じで
車輪接地状態のシミュレーション
gazeboを使ってシミュレーションしました。2cmの段差とスロープを配置して台車で乗り越えてみます。
想定通りに段差やスロープで接地してくれています。ちょっとキャスターの緩衝機構がふにゃふにゃで車両の揺れが気になります。実際の緩衝キャスターのばね定数を上げないとダメそうです。
シミュレーションデータ
上記シミュレーション用のURDFは次のgithubに公開しています。実行は下記のように行います。
$ mkdir -p catkin_ws/src
$ git clone ...
$ cd ..
$ source /opt/ros/melodic/setup.bash
$ catkin build
$ source devel/setup.bash
$ roslaunch agv_eval_description gazebo.launch sample:=sample3
シミュレーションのURDFはsample3です。
フロントのリンクとキャスター、駆動輪を1つのユニットしました。
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find agv_eval_description)/sample3/wheel/wheel.urdf.xacro"/>
<xacro:include filename="$(find agv_eval_description)/urdf/common.xacro"/>
<xacro:include filename="$(find agv_eval_description)/sample3/caster/caster.urdf.xacro"/>
<xacro:property name="caster_radius" value="${0.10/2}"/>
<xacro:property name="caster_length" value="0.04"/>
<xacro:property name="caster_mass" value="0.5"/>
<xacro:macro name="front_unit_v0" params="prefix parent *joint_origin *wheel_origin">
<joint name="${prefix}_arm_joint" type="revolute">
<xacro:insert_block name="joint_origin"/>
<parent link="${parent}"/>
<child link="${prefix}_arm_link"/>
<axis xyz="0 1 0"/>
<limit lower="-0.5" upper="0.5" effort="0" velocity="0"/>
<dynamics damping="0.7"/>
</joint>
<link name="${prefix}_arm_link">
<visual>
<origin xyz="0 0 0 " rpy="0 0 0"/>
<geometry>
<box size="0.035 0.07 0.43"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.035 0.07 0.43"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<xacro:box_inertial mass="0.2" height="0.1" width="0.05" depth="0.05"/>
</inertial>
</link>
<xacro:wheel_v0 prefix="${prefix}" parent="${prefix}_arm_link">
<xacro:insert_block name="wheel_origin"/>
<!--origin xyz="0.086 0 -0.14"/-->
<axis xyz="0 1 0"/>
</xacro:wheel_v0>
<xacro:caster_v0 prefix="${prefix}" parent="${prefix}_arm_link">
<origin xyz="0.01 0 0.2" rpy="0 -1.57 0"/>
</xacro:caster_v0>
</xacro:macro>
<xacro:macro name="caster_gazebo_v0" params="prefix">
<gazebo reference="${prefix}_caster_link">
<selfCollide>false</selfCollide>
<mu1 value="2.5" />
<mu2 value="2.5" />
<kp value="1e7" />
<kd value="1" />
<!--fdir1 value="1 0 0"/-->
<material>Gazebo/Black</material>
</gazebo>
</xacro:macro>
</robot>
おわりに
gazeboシミュレータをソフトウェア開発に使用することは多いと思います。機構開発においてもシミュレーションを行うことで「作ってみないとわからない」「動かさないとわからない」から少しでも事前の課題出しができることがわかりました。
次回はシミュレーション結果をもとに実際のAGVの設計を行います。メカに関しては素人なので色々と勉強しながら進めたいと思います。
予定を変更し、モーター駆動ソフトを先に着手しました。
Next