이번 포스팅은 이전 포스팅에서 구축한 환경을 기반으로 Gazebo를 이용해서 자동차 운전을 simulation 해보는 과정입니다.
이 포스트는 다음 영상의 내용을 기반으로 개발하고자 하는 로봇에 적합하게 수정했습니다.
Creating a rough 3D model of our robot with URDF
이 포스트는 다음 과정을 완료한 후에 참고하시길 바랍니다.
1. URDF를 Gazebo에서 로딩하기
- 이전 포스팅에서 URDF를 이용해서 만들었던 자동차를 Gazebo에서 로딩하는 과정입니다.
- 우선 아래 명령을 실행해서 'src/urdf_tutorial/urdf/robot_2.xacro' 파일을 'src/urdf_tutorial/urdf/robot_3.xacro' 파일로 복사합니다.
$ cd ~/Workspace/ros_ws
$ cp src/urdf_tutorial/urdf/robot_2.xacro src/urdf_tutorial/urdf/robot_3.xacro
- 다음은 ‘src/urdf_tutorial/launch/robot_3.launch.py’ 파일을 만들고 아래와 같이 편집합니다. 파일의 내용은 ‘src/urdf_tutorial/launch/robot_2.launch.py’에서 'robot_2.xacro'을 'robot_3.xacro'으로 변경했습니다.
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
import xacro
def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time")
pkg_path = os.path.join(get_package_share_directory("urdf_tutorial"))
xacro_file = os.path.join(pkg_path, "urdf", "robot_3.xacro")
robot_description = xacro.process_file(xacro_file)
params = {"robot_description": robot_description.toxml(), "use_sim_time": use_sim_time}
return LaunchDescription(
[
DeclareLaunchArgument(
"use_sim_time", default_value="false", description="use sim time"
),
Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="screen",
parameters=[params],
),
]
)
- 첫 번째 터미널에서 아래 명령을 실행해서 ‘robot_state_publisher’를 실행합니다. 이때 use_sim_time 옵션을 true로 설정해서 simulation mode를 활성화했습니다.
$ cd ~/Workspace/ros_ws
$ colcon build --symlink-install
$ source install/setup.bash
$ ros2 launch urdf_tutorial robot_3.launch.py use_sim_time:=true
- 다음은 두 번째 터미널에서 아래 명령을 실행해서 Gazebo를 실행합니다.
$ ros2 launch gazebo_ros gazebo.launch.py
- 아래와 같이 빈 화면이 출력되는 것을 확인할 수 있습니다. 아직 urdf 정보를 읽어오지 못했기 때문입니다.
- 세 번째 터미널에서 gazebo에 'roboto_description' Topic을 spawn 합니다.
$ ros2 run gazebo_ros spawn_entity.py -topic robot_description -entity with_robot
- 아래 그림과 같이 이전 포스팅에서 만들었던 자동차가 Gazebo에 출력됩니다.
- ROS를 실행하고 Gazebo를 실행하고 Spawn 하는 과정이 조금은 복잡합니다. 이 과정을 하나의 Script로 만들어서 한꺼번에 실행할 수 있도록 하겠습니다. ‘src/urdf_tutorial/launch/sim.launch.py’ 파일을 만들고 아래와 같이 편집합니다. 이 파일은 launch_sim.launch.py 파일의 내용을 일부 수정한 것입니다.
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node
def generate_launch_description():
package_name = "urdf_tutorial"
rsp = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[os.path.join(get_package_share_directory(package_name), "launch", "robot_3.launch.py")]
),
launch_arguments={"use_sim_time": "true"}.items(),
)
# Include the Gazebo launch file, provided by the gazebo_ros package
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[os.path.join(get_package_share_directory("gazebo_ros"), "launch", "gazebo.launch.py")]
),
)
# Run the spawner node from the gazebo_ros package. The entity name doesn't really matter if you only have a single robot.
spawn_entity = Node(
package="gazebo_ros",
executable="spawn_entity.py",
arguments=["-topic", "robot_description", "-entity", "with_robot"],
output="screen",
)
# Launch them all!
return LaunchDescription(
[
rsp,
gazebo,
spawn_entity,
]
)
- 'src/urdf_tutorial/urdf/robot_3.xacro' 파일을 수정해서 Gazebo가 색깔을 출력할 수 있도록 합니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">
<!-- MACROS -->
<xacro:include filename="macros.xacro"/>
<!-- COLOR -->
<material name="white">
<color rgba="1 1 1 1" />
</material>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<!-- BASE LINK -->
<link name="base_link">
</link>
<!-- BODY LINK -->
<joint name="body_joint" type="fixed">
<parent link="base_link"/>
<child link="body"/>
<origin xyz="-0.12 0 0"/>
</joint>
<link name="body">
<visual>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.2" y="0.1" z="0.06">
<origin xyz="0.1 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>
<gazebo reference="body">
<material>Gazebo/White</material>
</gazebo>
<!-- LEFT WHEEL LINK -->
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
<axis xyz="0 0 1"/>
</joint>
<link name="left_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="left_wheel">
<material>Gazebo/Black</material>
</gazebo>
<!-- RIGHT WHEEL LINK -->
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0 -0.065 0" rpy="${pi/2} 0 0" />
<axis xyz="0 0 -1"/>
</joint>
<link name="right_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="right_wheel">
<material>Gazebo/Black</material>
</gazebo>
<!-- CASTER WHEEL LINK -->
<joint name="caster_wheel_joint" type="fixed">
<parent link="body"/>
<child link="caster_wheel"/>
<origin xyz="0.03 0 0"/>
</joint>
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="0.1" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>
<gazebo reference="caster_wheel">
<material>Gazebo/Blue</material>
<mu1 value="0.001"/>
<mu2 value="0.001"/>
</gazebo>
</robot>
- 실행 중인 모든 프로그램을 종료한 뒤 첫 번째 터미널에서 아래 명령을 실행해서 'sim.launch.py'를 실행합니다.
$ cd ~/Workspace/ros_ws
$ colcon build --symlink-install
$ source install/setup.bash
$ ros2 launch urdf_tutorial sim.launch.py
- 아래 그림과 같이 Gazebo에 출력되는 자동차에 색이 추가된 것을 확인할 수 있습니다.
2. Gazebo에서 자동차 운전하기
- Gazebo에 자동차를 조절할 수 있는 Plugin을 로딩하고 키보드를 이용해 운전해 보는 과정입니다.
- Gazebo가 diff_dirver Plugin을 사용해서 운전 simulation을 할 수 있도록 ‘src/urdf_tutorial/urdf/gazebo.xacro’ 파일에 아래 내용을 추가합니다. Gazebo plugins in ROS에 접속하시면 Gazebo에서 사용가능한 다양한 Plugin을 확인할 수 있습니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<gazebo>
<plugin name="diff_drive" filename="libgazebo_ros_diff_drive.so">
<!-- Wheel Information -->
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>0.35</wheel_separation>
<wheel_diameter>0.1</wheel_diameter>
<!-- Limits -->
<max_wheel_torque>200</max_wheel_torque>
<max_wheel_acceleration>10.0</max_wheel_acceleration>
<!-- Output -->
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_link</robot_base_frame>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>true</publish_wheel_tf>
</plugin>
</gazebo>
</robot>
- 'src/urdf_tutorial/urdf/robot_3.xacro' 파일을 편집해서 'src/urdf_tutorial/urdf/gazebo.xacro' 파일을 include 합니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">
<!-- MACROS -->
<xacro:include filename="macros.xacro"/>
<!-- COLOR -->
<material name="white">
<color rgba="1 1 1 1" />
</material>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<!-- BASE LINK -->
<link name="base_link">
</link>
<!-- BODY LINK -->
<joint name="body_joint" type="fixed">
<parent link="base_link"/>
<child link="body"/>
<origin xyz="-0.12 0 0"/>
</joint>
<link name="body">
<visual>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.2" y="0.1" z="0.06">
<origin xyz="0.1 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>
<gazebo reference="body">
<material>Gazebo/White</material>
</gazebo>
<!-- LEFT WHEEL LINK -->
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
<axis xyz="0 0 1"/>
</joint>
<link name="left_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="left_wheel">
<material>Gazebo/Black</material>
</gazebo>
<!-- RIGHT WHEEL LINK -->
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0 -0.065 0" rpy="${pi/2} 0 0" />
<axis xyz="0 0 -1"/>
</joint>
<link name="right_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="right_wheel">
<material>Gazebo/Black</material>
</gazebo>
<!-- CASTER WHEEL LINK -->
<joint name="caster_wheel_joint" type="fixed">
<parent link="body"/>
<child link="caster_wheel"/>
<origin xyz="0.03 0 0"/>
</joint>
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="0.1" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>
<gazebo reference="caster_wheel">
<material>Gazebo/Blue</material>
<mu1 value="0.001"/>
<mu2 value="0.001"/>
</gazebo>
<!-- GAZEBO -->
<xacro:include filename="gazebo.xacro"/>
</robot>
- 첫 번째 터미널에서 ‘CTRL+C’를 눌러서 프로그램을 종료하고 아래 명령을 실행해서 ‘sim.launch.py’를 다시 실행합니다.
$ colcon build --symlink-install
$ ros2 launch urdf_test sim.launch.py
- 키보드를 이용해 자동차를 조정해 보기 위해서 두 번째 터미널에서 아래 명령을 실행해서 ‘teleop_twist_keyboard’를 실행합니다.
$ ros2 run teleop_twist_keyboard teleop_twist_keyboard
- 아래 화면을 활성화한 후 ‘u’, ‘i’, ‘o’ 등의 키를 입력합니다.
- 아래 그림과 같이 자동차가 움직이는 것을 확인할 수 있습니다.
- 세 번째 터미널에서 아래 명령을 실행해서 Rviz를 실행하고 저장된 'src/urdf_tutorial/config/robot.rviz'를 읽어 옵니다.
$ rviz2
- Rviz에서 'Fixed Frame'을 'odom'으로 변경 후 teleop_twist_keyboard 화면에서 키를 입력하면 Gazebo와 Rviz에서 동시에 자동차가 움직이는 것을 확인할 수 있습니다.
- 네 번째 터미널에서 아래 명령을 실행해서 'rqt_graph'를 실행합니다.
$ rqt_graph
- 아래 그림과 같이 ROS에서 주고받는 Topic을 확인할 수 있습니다.
'로봇 > ROS' 카테고리의 다른 글
Gazebo를 이용해 2D LiDAR 시뮬레이션 하기 (2) | 2023.07.22 |
---|---|
ROS2 Transformation System (TF2) (0) | 2023.07.19 |
URDF를 이용한 간단한 로봇 만들기 (2) (0) | 2023.07.16 |
URDF를 이용한 간단한 로봇 만들기 (1) (2) | 2023.07.15 |
ROS2 Minimal Tutorial - Action (0) | 2023.07.14 |