로봇 모델 시각화
Moby Description 패키지
moby_description
패키지는 RViz 및 Gazebo 시뮬레이터에서 사용할 모델 파일(URDF)을 포함하고 있습니다.
로봇 모델
- URDF (The Universal Robotic Description Format): 로봇의 기구학 및 동역학적 요소를 기술하는 XML 형식 파일입니다.
- Xacro: XML + Macro의 합성어로 로봇모델을 간단하게 메크로를 사용하여 XML 파일을 생성 할 수 있게 해줍니다.
moby_description
패키지의 urdf 폴더에는, Moby 모델(MobyRP, MobyRP_V3)의 모든 구성을 포함하는 config
폴더가 있습니다. 다른 xacro 파일은 config
폴더의 파일을 읽고 로봇을 구성합니다.
아래 다이어그램은 파일 간의 관계를 보여줍니다.
joint_limits ────────┐
kinematics ──────────┤
physical_parameters ─┤
visual_parameters ───┤
moby_common ─┤
moby_transmission ─┤
materials ─┴─ moby_macro─moby.urdf
urdf 및 xacro에 대한 자세한 정보는 아래 링크를 참고하십시오. * ROS2 Humble build model tutorial
Rviz 실행
Moby 모델은 RViz2를 통해 시각화 될 수 있습니다. launch 파일은 한 번에 여러 ROS 노드를 시작하는 파일입니다. 다음 명령어를 통해 ROS2에서 robot description을 실행하고 로봇 모델을 시각화 할 수 있습니다.
moby_type
을 "moby_rp"로 지정하면, launch 파일이 적절한 구성 파일을 로드하고 RViz와 같은 시각화 도구에 로봇을 표시하는 데 필요한 노드를 실행합니다.
실행 후 Rviz 화면을 확인할 수 있습니다.
joint_states_publisher
의 joint position 값을 수정하는 것으로, RViz에서 Indy의 관절과 Moby 바퀴의 위치를 변경할 수 있습니다.
Launch 파일
아래의 코드는 위의 명령에서의 moby_display.launch.py입니다.
#!/usr/bin/python3
#-*- coding: utf-8 -*-
from launch_ros.actions import Node
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
def generate_launch_description():
# Declare arguments
declared_arguments = []
declared_arguments.append(
DeclareLaunchArgument(
"name",
default_value="moby"
)
)
declared_arguments.append(
DeclareLaunchArgument(
"moby_type",
default_value="moby_rp",
description="Type of Moby robot.",
choices=["moby_rp", "moby_rp_v3"]
)
)
declared_arguments.append(
DeclareLaunchArgument(
"prefix",
default_value='""',
description="Prefix of the joint names, useful for \
multi-robot setup. If changed than also joint names in the controllers configuration \
have to be updated."
)
)
# Initialize Arguments
name = LaunchConfiguration("name")
moby_type = LaunchConfiguration("moby_type")
prefix = LaunchConfiguration("prefix")
description_package = FindPackageShare('moby_description')
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution([description_package, "urdf", 'moby.urdf.xacro']),
" ",
"name:=",
name,
" ",
"moby_type:=",
moby_type,
" ",
"prefix:=",
prefix
]
)
robot_description = {"robot_description": robot_description_content}
rviz_config_file = PathJoinSubstitution(
[description_package, "rviz_config", "moby.rviz"]
)
robot_state_publisher_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="screen",
parameters=[robot_description]
)
joint_state_publisher_gui_node = Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui'
)
rviz_node = Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", rviz_config_file]
)
nodes = [
joint_state_publisher_gui_node,
robot_state_publisher_node,
rviz_node,
]
return LaunchDescription(declared_arguments + nodes)
-
robot_description:
moby.urdf.xacro
를 읽고,joint_state_publisher
노드에 관련된 파라미터입니다. -
joint_state_publisher:
robot_description
의 관절 및 바퀴 위치를 /joint_states 토픽으로 발행합니다. -
robot_state_publisher: /joint_states 토픽을 구독하고 각 링크의 transform을 발행합니다.
-
rviz : RViz 노드를 실행하고, rviz 설정 파일 (moby_description/rviz_config/moby.rviz)을 로드합니다.
robot_state_publisher
노드에서 발행된tf
를 구독하고 시각화합니다.