Jetson Nano + ROS で四足歩行ロボットをシミュレーションしてみる(Gazebo)では、Gazeboで四つ足ロボットを動かしてみました。
ここでは車輪(Wheel)を4つ持っているロボットを動かしてみます。
車輪の型としてはメカナムホイールを使ってみます(オムニホイールと対で説明されることが多いようです)。
この車輪を使ったロボットは駆動輪の回転差で旋回や移動をします。移動は全方向への平行移動が可能です。
四輪ローバーを使ったシミュレーションパッケージをヴィストン株式会社さんが公開されています(ありがたいことです)。
まずは、このロボットを使わせていただいて、最後にシンプルな形状に改変してみます。
使われているパーツ、右下にあるのがwheelとbarrelという部品です。
ホイールとバレルの関係、45度の角度で接続されています。
バレルは15個使われています。
以下をセットアップしておきます。
ROS1(Melodic)
CHAMPパッケージ
キーボード制御用パッケージ
PS4コントローラ用ライブラリ
ROS1(Melodic)
使用するプラットフォームはJetson Nano (Jetpack 4.6)
Jetson Nano にROS1 (Melodic) をインストール(メモ)
CHAMPパッケージインストール
CHAMPを参照
1 2 3 4 5 6 7 8 9 10 11 |
sudo apt install -y python-rosdep cd ~/catkin_ws/src git clone --recursive https://github.com/chvmp/champ git clone https://github.com/chvmp/champ_teleop cd ~/catkin_ws rosdep install --from-paths src --ignore-src -r -y |
キーボード制御用パッケージ
teleop_twist_keyboardインストール
1 |
sudo apt install ros-melodic-teleop-twist-keyboard |
PS4コントローラ(ゲームパッド)のドライバをインストール
1 |
sudo apt install ros-melodic-joy ros-melodic-joystick-drivers -y |
PS4コントローラをBluetooth接続して、デバイスアサインを見てみます。
1 |
ls -al /dev/input |
joycon.launchをエディターで開きます
1 |
sudo nano ~/catkin_ws/src/mecanumrover_samples/launch/joycon.launch |
valueが同じかどうか確認、違っていたら修正
<param name=”dev” type=”string” value=“/dev/input/js0” />
メカナムローバーのサンプルROSパッケージをGithub からクローンしてインストール
1 2 3 4 5 6 7 |
cd ~/catkin_ws/src git clone https://github.com/vstoneofficial/mecanumrover_samples.git cd ~/catkin_ws catkin_make |
ワークスペースをオーバーレイ
1 |
source ~/catkin_ws/devel/setup.bash |
端末起動時に自動的にオーバーレイが実行されるようにしておきます。
1 2 3 |
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc source ~/.bashrc |
PS4コントローラで制御
ローバーを起動
1 |
roslaunch mecanumrover_samples vmecanumrover_withworld.launch |
デフォルトではLiDARの青いレーザが可視化されています。
消す場合は以下を編集
1 |
sudo nano ~/catkin_ws/src/mecanumrover_samples/urdf/vmecanumrover.xacro |
<gazebo reference=”lidar_link”>タグの中の<visualize>をfalseに設定
別のターミナルを開いて、以下のコマンドで、joycon.launch を呼び出します。
1 |
roslaunch mecanumrover_samples joycon.launch |
さらに別ターミナルを開いて、/rover_twistというtopicを確認します。
1 |
rostopic echo /rover_twist |
コマンドが実行されたら、コントローラのこのボタン(3番)を押し込みます。
以下のようにメカナム ローバーに送信されているパラメータが確認できます。
ローバーの制御は、3番ボタンを押しながら、左スティックで行います。
GazeboでNavigation
Gazeboを起動
1 |
roslaunch mecanumrover_samples vmecanumrover_withworld.launch |
Rvizを起動
1 |
roslaunch mecanumrover_samples mecanumrover_move_base.launch |
2D Nav Goal で移動地点と次の進行方向を指示します。
ルートが設定されて、Navigationが開始されます。
キーボードで制御
Gazeboを起動
1 |
roslaunch mecanumrover_samples vmecanumrover_withworld.launch |
teleoperationで制御してみます。
1 |
rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=/rover_twist |
大文字のJ、L、U、O、M、>で左右斜めに進みます。
こんな感じ。
全方向移動をするメカナムホイールがどんな動きをしているのか見てみます
シンプルにモデルをホイールとモータシャフトだけにします(bodyなどは非表示)。
車輪の動きを見る際には動きまわられると見づらくなるので、バレルの摩擦係数を0.0にして車輪が回転しても移動しないようにします。
注:以下の動画はFirefoxだと見えないかも…ChromeかEdgeでお試しください
前進・後退
旋回
超信地旋回
斜め平行移動
左右平行移動
シンプルローバー作成
以下のファイを改変してbody、wheel、barrel、sus、motor、lidarだけの簡単なローバーを作成してみます。
~/catkin_ws/src/mecanumrover_samples/urdf/vmecanumrover.xacro
~/catkin_ws/src/mecanumrover_samples/launch/vmecanumrover.launch
こんな感じ
~/catkin_ws/src/mecanumrover_samples/urdf/vmecanumrover.xacro
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 |
<?xml version="1.0"?> <robot name="vmecanumrover" xmlns:xacro="http://ros.org/wiki/xacro"> <link name="base_link"/> <xacro:macro name="cylinder_inertial" params="mass radius length"> <mass value="${mass}"/> <inertia ixx="${((radius*radius)/4 + (length*length)/12)*mass}" ixy="0" ixz="0" iyy="${((radius*radius)/4 + (length*length)/12)*mass}" iyz="0" izz="${(mass*radius*radius)/2}" /> </xacro:macro> <xacro:macro name="box_inertial" params="mass height width depth"> <mass value="${mass}"/> <inertia ixx="${(mass*(width*width+depth*depth))/12}" ixy="0" ixz="0" iyy="${(mass*(height*height+depth*depth))/12}" iyz="0" izz="${(mass*(height*height+width*width))/12}" /> </xacro:macro> <!-- ==================================== --> <xacro:macro name="sus" params="prefix"> <joint name="${prefix}_sus_joint" type="prismatic"> <parent link="${prefix}_base_link"/> <child link="${prefix}_sus_link"/> <limit lower="-0.02" upper="0.02" effort="100" velocity="1.0" /> <axis xyz="0 0 1"/> <origin xyz="0 0 0" rpy="0 0 0"/> <dynamics damping="0.01"/> </joint> <transmission name="${prefix}_sus_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${prefix}_sus_joint"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="${prefix}_sus_motor"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanismReduction>1</mechanismReduction> </actuator> </transmission> <gazebo reference="${prefix}_sus_joint"> <kp>50000</kp> <kd>500</kd> </gazebo> <link name="${prefix}_sus_link"> <inertial> <mass value="0.010"/> <inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001"/> </inertial> </link> </xacro:macro> <!-- ==================================== --> <xacro:macro name="barrel" params="prefix num dir rot"> <joint name="${prefix}_barrel${num}_joint" type="continuous"> <parent link="${prefix}_motor_shaft_link"/> <child link="${prefix}_barrel${num}_link"/> <origin rpy="${pi/4*rot} 0 ${radians(dir)}" xyz="${0.0666389*cos(radians(dir))} ${0.0666389*sin(radians(dir))} 0"/> <axis xyz="0 0 1"/> <dynamics damping="0.001" friction="0.0"/> </joint> <link name="${prefix}_barrel${num}_link"> <visual> <geometry> <mesh filename="package://mecanumrover_samples/meshes/dae/mecanum_barrel.dae" /> </geometry> <material name="black"/> </visual> <collision> <geometry> <cylinder radius="0.00956" length="0.0381" /> </geometry> </collision> <inertial> <xacro:cylinder_inertial mass="0.01225" radius="0.00956" length="0.0381" /> </inertial> </link> <gazebo reference="${prefix}_barrel${num}_link"> <material>Gazebo/Black</material> <mu1 value="2.5" /> <mu2 value="2.5" /> <kp value="50000" /> <kd value="100" /> </gazebo> </xacro:macro> <xacro:macro name="barrels" params="prefix rot "> <xacro:barrel prefix="${prefix}" num="0" dir="0" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="1" dir="24" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="2" dir="48" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="3" dir="72" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="4" dir="96" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="5" dir="120" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="6" dir="144" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="7" dir="168" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="8" dir="192" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="9" dir="216" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="10" dir="240" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="11" dir="264" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="12" dir="288" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="13" dir="312" rot="${rot}"/> <xacro:barrel prefix="${prefix}" num="14" dir="336" rot="${rot}"/> </xacro:macro> <!-- ==================================== --> <xacro:macro name="motor" params="prefix parent mesh"> <joint name="${prefix}_joint" type="fixed"> <parent link="${parent}"/> <child link="${prefix}_body_link"/> </joint> <link name="${prefix}_body_link"> <visual> <origin rpy="0 ${radians(90)} 0" xyz="-0.06075 0 0"/> <geometry> <cylinder radius="0.02225" length="0.1215" /> </geometry> <material name="gray"/> </visual> <collision> <origin rpy="0 ${radians(90)} 0" xyz="-0.06075 0 0"/> <geometry> <cylinder radius="0.02225" length="0.1215" /> </geometry> </collision> <inertial> <xacro:cylinder_inertial mass="0.880" radius="0.02225" length="0.1215" /> </inertial> </link> <gazebo reference="${prefix}_body_link"> <material>Gazebo/Gray</material> </gazebo> <joint name="${prefix}_shaft_joint" type="continuous"> <parent link="${prefix}_body_link"/> <child link="${prefix}_shaft_link"/> <origin rpy="0 ${radians(90)} 0" xyz="0 0 0"/> <axis xyz="0 0 -1"/> <!-- <limit velocity="40.0" effort="3.0" /> --> <dynamics damping="0.01" friction="0.0"/> </joint> <transmission name="${prefix}_shaft_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${prefix}_shaft_joint"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="${prefix}_shaft_motor"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> <link name="${prefix}_shaft_link"> <visual> <geometry> <mesh filename="package://mecanumrover_samples/meshes/dae/${mesh}.dae" /> </geometry> <material name="gray"/> </visual> <collision> <origin rpy="0 0 0" xyz="0 0 0"/> <geometry> <!-- <cylinder radius="0.048" length="0.04572" /> --> <cylinder radius="0.070" length="0.04572" /> <!-- <mesh filename="package://mecanumrover_samples/meshes/stl/${mesh}.stl" /> --> </geometry> </collision> <inertial> <xacro:cylinder_inertial mass="0.43525" radius="0.048" length="0.04572" /> </inertial> </link> <gazebo reference="${prefix}_shaft_link"> <material>Gazebo/White</material> <mu1 value="0.0" /> <mu2 value="0.0" /> </gazebo> </xacro:macro> <!-- ==================================== --> <xacro:macro name="omni_wheel_set_l" params="prefix parent"> <joint name="${prefix}_base_joint" type="fixed"> <parent link="${parent}"/> <child link="${prefix}_base_link"/> <origin rpy="0 0 0" xyz="0 0 0"/> </joint> <link name="${prefix}_base_link" > <inertial> <mass value="0.010"/> <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/> </inertial> </link> <xacro:sus prefix="${prefix}"/> <xacro:motor prefix="${prefix}_motor" parent="${prefix}_sus_link" mesh="mecanum_wheel_rev"/> <xacro:barrels prefix="${prefix}" rot="-1"/> </xacro:macro> <xacro:macro name="omni_wheel_set_r" params="prefix parent"> <joint name="${prefix}_base_joint" type="fixed"> <parent link="${parent}"/> <child link="${prefix}_base_link"/> <origin rpy="0 0 0" xyz="0 0 0"/> </joint> <link name="${prefix}_base_link" > <inertial> <mass value="0.010"/> <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/> </inertial> </link> <xacro:sus prefix="${prefix}"/> <xacro:motor prefix="${prefix}_motor" parent="${prefix}_sus_link" mesh="mecanum_wheel"/> <xacro:barrels prefix="${prefix}" rot="1"/> </xacro:macro> <!-- ==================================== --> <joint name="body_joint" type="fixed"> <parent link="base_link"/> <child link="body_link"/> <origin xyz="0 0 0.10" rpy="0 0 0"/> </joint> <link name="body_link"> <visual> <geometry> <box size="0.30 0.20 0.10"/> </geometry> <material name="gray"/> </visual> <collision> <geometry> <box size="0.30 0.20 0.10"/> </geometry> </collision> <inertial> <xacro:box_inertial mass="20.00" height="0.10" width="0.20" depth="0.30" /> </inertial> </link> <gazebo reference="body_link"> <material>Gazebo/BlueTransparent</material> </gazebo> <joint name="wheel0_attach_joint" type="fixed"> <parent link="base_link"/> <child link="wheel0_attach_link"/> <origin xyz="0.115 0.132 0.075" rpy="0 0 ${radians(90)}"/> </joint> <link name="wheel0_attach_link" /> <xacro:omni_wheel_set_l prefix="wheel0" parent="wheel0_attach_link" /> <joint name="wheel1_attach_joint" type="fixed"> <parent link="base_link"/> <child link="wheel1_attach_link"/> <origin xyz="0.115 -0.132 0.075" rpy="0 0 ${radians(-90)}"/> </joint> <link name="wheel1_attach_link" /> <xacro:omni_wheel_set_r prefix="wheel1" parent="wheel1_attach_link" /> <joint name="wheel2_attach_joint" type="fixed"> <parent link="base_link"/> <child link="wheel2_attach_link"/> <origin xyz="-0.115 0.132 0.075" rpy="0 0 ${radians(90)}"/> </joint> <link name="wheel2_attach_link" /> <xacro:omni_wheel_set_r prefix="wheel2" parent="wheel2_attach_link" /> <joint name="wheel3_attach_joint" type="fixed"> <parent link="base_link"/> <child link="wheel3_attach_link"/> <origin xyz="-0.115 -0.132 0.075" rpy="0 0 ${radians(-90)}"/> </joint> <link name="wheel3_attach_link" /> <xacro:omni_wheel_set_l prefix="wheel3" parent="wheel3_attach_link" /> <!-- ==================================== --> <!-- LiDAR --> <joint name="lidar_joint" type="fixed"> <parent link="base_link"/> <child link="lidar_link"/> <origin xyz="0.0 0 0.20" rpy="0 0 0"/> </joint> <link name="lidar_link"> <visual> <geometry> <mesh filename="package://mecanumrover_samples/meshes/dae/mecanum_lidar.dae" /> </geometry> <material name="black"/> </visual> <collision> <geometry> <mesh filename="package://mecanumrover_samples/meshes/stl/mecanum_lidar.stl" /> </geometry> </collision> <inertial> <xacro:box_inertial mass="0.160" height="0.07" width="0.05" depth="0.05" /> </inertial> </link> <gazebo reference="lidar_link"> <material>Gazebo/Black</material> <sensor type="ray" name="lidar_sensor"> <pose>0 0 0 0 0 0</pose> <visualize>false</visualize> <update_rate>40</update_rate> <ray> <scan> <horizontal> <samples>1000</samples> <resolution>1</resolution> <min_angle>-1.57</min_angle> <max_angle>1.57</max_angle> </horizontal> </scan> <range> <min>0.06</min> <max>4.0</max> <resolution>0.001</resolution> </range> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.03</stddev> </noise> </ray> <plugin name="gazebo_ros_lrf_controller" filename="libgazebo_ros_laser.so"> <topicName>/scan</topicName> <frameName>lidar_link</frameName> </plugin> </sensor> </gazebo> <!-- ==================================== --> <gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/vmecanumrover</robotNamespace> <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> <legacyModeNS>true</legacyModeNS> <odometryFrame>map</odometryFrame> </plugin> </gazebo> </robot> |
~/catkin_ws/src/mecanumrover_samples/launch/vmecanumrover.launch
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 |
<?xml version="1.0" encoding="UTF-8"?> <launch> <arg name="model" default="$(find mecanumrover_samples)/urdf/vmecanumrover.xacro" /> <arg name="world" default="" /> <arg name="rvizconfig" default="$(find mecanumrover_samples)/conf.rviz" /> <arg name="rover_d" default="0.133" /> <arg name="rover_hb" default="0.115" /> <arg name="wheel_circumference" default="0.4775" /> <arg name="f_l" default="0" /> <arg name="f_r" default="1" /> <arg name="r_l" default="2" /> <arg name="r_r" default="3" /> <param name="robot_description" command="$(find xacro)/xacro $(arg model) --inorder"/> <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="world_name" value="$(arg world)"/> <arg name="paused" value="false"/> <arg name="use_sim_time" value="true"/> <arg name="gui" value="true"/> <arg name="headless" value="false"/> <arg name="debug" value="false"/> </include> <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model vmecanumrover" /> <rosparam command="load" file="$(find mecanumrover_samples)/configuration_files/vmecanumrover_move_controller.yaml" ns="vmecanumrover"/> <rosparam command="load" file="$(find mecanumrover_samples)/configuration_files/vmecanumrover_sus_controller.yaml" ns="vmecanumrover"/> <rosparam command="load" file="$(find mecanumrover_samples)/configuration_files/vmecanumrover_joint_state_controller.yaml" ns="vmecanumrover"/> <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/vmecanumrover" args="joint_controller0 joint_controller1 joint_controller2 joint_controller3 sus_controller0 sus_controller1 sus_controller2 sus_controller3 joint_state_controller"/> <node name="vmecanum_twist" pkg="mecanumrover_samples" type="vmecanum_twist" output="screen"> <param name="rover_d" value="$(arg rover_d)"/> <param name="rover_hb" value="$(arg rover_hb)"/> <param name="wheel_circumference" value="$(arg wheel_circumference)"/> <param name="f_l" value="$(arg f_l)"/> <param name="f_r" value="$(arg f_r)"/> <param name="r_l" value="$(arg r_l)"/> <param name="r_r" value="$(arg r_r)"/> <remap from="wheel0" to="/vmecanumrover/joint_controller0/command" /> <remap from="wheel1" to="/vmecanumrover/joint_controller1/command" /> <remap from="wheel2" to="/vmecanumrover/joint_controller2/command" /> <remap from="wheel3" to="/vmecanumrover/joint_controller3/command" /> </node> <node name="vmecanum_odom" pkg="mecanumrover_samples" type="vmecanum_odom" output="screen"> <param name="rover_d" value="$(arg rover_d)"/> <param name="rover_hb" value="$(arg rover_hb)"/> <param name="wheel_circumference" value="$(arg wheel_circumference)"/> <param name="f_l" value="$(arg f_l)"/> <param name="f_r" value="$(arg f_r)"/> <param name="r_l" value="$(arg r_l)"/> <param name="r_r" value="$(arg r_r)"/> <remap from="wheel0/state" to="/vmecanumrover/joint_controller0/state" /> <remap from="wheel1/state" to="/vmecanumrover/joint_controller1/state" /> <remap from="wheel2/state" to="/vmecanumrover/joint_controller2/state" /> <remap from="wheel3/state" to="/vmecanumrover/joint_controller3/state" /> </node> <node name="vmecanum_liftup_sus" pkg="mecanumrover_samples" type="vmecanum_liftup_sus" respawn="false" output="screen"> <remap from="sus0" to="/vmecanumrover/sus_controller0/command" /> <remap from="sus1" to="/vmecanumrover/sus_controller1/command" /> <remap from="sus2" to="/vmecanumrover/sus_controller2/command" /> <remap from="sus3" to="/vmecanumrover/sus_controller3/command" /> </node> </launch> |
起動
1 |
roslaunch mecanumrover_samples vmecanumrover_withworld.launch |
其の他詳細
Appendix
三輪走行ロボットのシミュレーション
gazeboによる,オムニホイール型ロボットのシミュレーション環境構築
Leave a Reply