URDFファイルで記述したロボットのシミュレーションロボットを動かすための手順は
1. Gazeboの起動
2. ロボットモデルをrobot_descriptionにloadする
3. robot_state_publisherの起動
4. ロボットモデルをGazebo上にスポーンさせる(urdf_spawner)
5. ロボットのコントローラを読み込む
2. ロボットモデルをrobot_descriptionにloadする
3. robot_state_publisherの起動
4. ロボットモデルをGazebo上にスポーンさせる(urdf_spawner)
5. ロボットのコントローラを読み込む
この後にJoyコントローラを起動して、ロボットがSubscribeしているトピックに指令値を流せばGazebo上のロボットが動き回ります。
gazeboで実験用シミュレーション環境をつくりたので、とりあえずURDFで記述したロボットをrobot_state_publisher
で表示してみる。
目次
1. 必要ライブラリのインストール
2. URDFでロボットを記述
3. URDFの書き方
4. 表示用のlaunchファイル
5. rvizで表示
6.URDFロボットの関係図
1. 必要ライブラリのインストール
$ sudo apt install ros-noetic-joint-state-publisher-gui # パッケージの作成 $ catkin_create_pkg viz_urdf std_msgs rospy roscpp tf $ mkdir urdf launch $ sudo cp /opt/ros/noetic/share/urdf_tutorial/launch/display.launch launch $ sudo chmod 755 -R *
2. URDFでロボットを記述
urdfファイル(car_robot.urdf)<?xml version="1.0"?> <robot name="visual"> <material name="blue"> <color rgba="0 0 0.8 1"/> </material> <material name="black"> <color rgba="0 0 0 1"/> </material> <material name="white"> <color rgba="1 1 1 1"/> </material> <link name="base_link"> <visual> <geometry> <cylinder length="0.6" radius="0.2"/> </geometry> <material name="blue"/> </visual> </link> <link name="right_leg"> <visual> <geometry> <box size="0.6 0.1 0.2"/> </geometry> <origin rpy="0 1.57075 0" xyz="0 0 -0.3"/> <material name="white"/> </visual> </link> <joint name="base_to_right_leg" type="fixed"> <parent link="base_link"/> <child link="right_leg"/> <origin xyz="0 -0.22 0.25"/> </joint> <link name="right_base"> <visual> <geometry> <box size="0.4 0.1 0.1"/> </geometry> <material name="white"/> </visual> </link> <joint name="right_base_joint" type="fixed"> <parent link="right_leg"/> <child link="right_base"/> <origin xyz="0 0 -0.6"/> </joint> <link name="right_front_wheel"> <visual> <origin rpy="1.57075 0 0" xyz="0 0 0"/> <geometry> <cylinder length="0.1" radius="0.035"/> </geometry> <material name="black"/> </visual> </link> <joint name="right_front_wheel_joint" type="fixed"> <parent link="right_base"/> <child link="right_front_wheel"/> <origin rpy="0 0 0" xyz="0.133333333333 0 -0.085"/> </joint> <link name="right_back_wheel"> <visual> <origin rpy="1.57075 0 0" xyz="0 0 0"/> <geometry> <cylinder length="0.1" radius="0.035"/> </geometry> <material name="black"/> </visual> </link> <joint name="right_back_wheel_joint" type="fixed"> <parent link="right_base"/> <child link="right_back_wheel"/> <origin rpy="0 0 0" xyz="-0.133333333333 0 -0.085"/> </joint> <link name="left_leg"> <visual> <geometry> <box size="0.6 0.1 0.2"/> </geometry> <origin rpy="0 1.57075 0" xyz="0 0 -0.3"/> <material name="white"/> </visual> </link> <joint name="base_to_left_leg" type="fixed"> <parent link="base_link"/> <child link="left_leg"/> <origin xyz="0 0.22 0.25"/> </joint> <link name="left_base"> <visual> <geometry> <box size="0.4 0.1 0.1"/> </geometry> <material name="white"/> </visual> </link> <joint name="left_base_joint" type="fixed"> <parent link="left_leg"/> <child link="left_base"/> <origin xyz="0 0 -0.6"/> </joint> <link name="left_front_wheel"> <visual> <origin rpy="1.57075 0 0" xyz="0 0 0"/> <geometry> <cylinder length="0.1" radius="0.035"/> </geometry> <material name="black"/> </visual> </link> <joint name="left_front_wheel_joint" type="fixed"> <parent link="left_base"/> <child link="left_front_wheel"/> <origin rpy="0 0 0" xyz="0.133333333333 0 -0.085"/> </joint> <link name="left_back_wheel"> <visual> <origin rpy="1.57075 0 0" xyz="0 0 0"/> <geometry> <cylinder length="0.1" radius="0.035"/> </geometry> <material name="black"/> </visual> </link> <joint name="left_back_wheel_joint" type="fixed"> <parent link="left_base"/> <child link="left_back_wheel"/> <origin rpy="0 0 0" xyz="-0.133333333333 0 -0.085"/> </joint> </robot>
3. URDFの書き方
「link」の属性
<visual> : 可視化情報 <origin>:重心位置 <mass>:物体の重さ <collision> : 衝突情報 <inertia>:慣性情報 <material>:gazeboで表示する色 <origin>:以下のgeometryの中心(省略可) <geometry>:(衝突判定に使う形の定義)
「joint」の属性
<parent> : 関節の親リンクの名前の指定。 <child> : 関節の子リンクの名前の指定。 <origin> : 親リンクの座標系から子リンクの座標系への相対座標の変換。 <axis> : 回転軸の定義。 <limit> : 関節の速度、力、回転角度の上限下限の指定。
4. 表示用のlaunchファイル
launchファイル(display.launch)
<launch> <!-- arg --> <arg name="model" default="$(find urdf_tutorial)/urdf/01-myfirst.urdf"/> <arg name="gui" default="true" /> <arg name="rvizconfig" default="$(find urdf_tutorial)/rviz/urdf.rviz" /> <!-- load model for parameter --> <param name="robot_description" command="$(find xacro)/xacro $(arg model)" /> <!-- running of joint_state_publisher --> <node if="$(arg gui)" name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" /> <node unless="$(arg gui)" name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" /> <!-- running of robot_state_publisher --> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" /> <!-- running of rviz --> <node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" /> </launch>
5. rvizで表示
# 表示
$ roslaunch viz_urdf display.launch model:=urdf/car_robot.urdf
$ tree viz_urdf
viz_urdf ├── CMakeLists.txt ├── include │ └── viz_urdf ├── launch │ └── display.launch ├── package.xml ├── src └── urdf ├── car_pole.urdf └── car_robot.urdf
6.URDFロボットの関係図
# check toolのinstall $ sudo apt-get install liburdfdom-tools # URDFの文法が正しいかcheck $ check_urdf urdf/car_robot.urdf >>> ### robot name is: visual ### ---------- Successfully Parsed XML --------------- ### root Link: base_link has 2 child(ren) ### child(1): left_leg ### child(1): left_base ### child(1): left_back_wheel ### child(2): left_front_wheel ### child(2): right_leg ### child(1): right_base ### child(1): right_back_wheel ### child(2): right_front_wheel # PDFファイルで関係図を作成 $ urdf_to_graphiz urdf/car_robot.urdf ### Created file visual.gv ### Created file visual.pdf # PDFの可視化 $ evince visual.pdf
参考
ROS入門 (24) - URDFによるロボットモデルの作成Installing gazebo_ros_pkgs (ROS 1)
Gazebo + ROS で自分だけのロボットをつくる 5. GazeboとROSの連携
ROS講座26 シミュレーターを作る