5장 ROS 도구 활용하기
1. RQT(QT-based framework for GUI development for ROS)
1. 1 Graph
현재 ROS상의 노드와 메세지간의 정보를 그래프형식으로 보여준다.
터틀심 노드 실행
rosrun turtlesim turtlesim_node터틀심 원격조종 노드 실행
rosrun turtlesim turtle_teleop_key노드 그래프 생성
rqt_graph
2. Plot
메세지의 값에 대해 plot을 그리게 해준다.
rosrun turtlesim turtlesim_noderosrun turtlesim turtle_teleop_keypose 메세지 plotting
rqt_plot /turtle1/pose/
터틀심 노드의 pose 메세지 값
터틀심 노드의 pose - time plot
3. Rosbag
메세지를 기록, 저장, 재생할 수 있게 해준다.
rosrun turtlesim turtlesim_noderosrun turtlesim turtle_teleop_key원하는 디렉토리에 다음 명령어를 실행하면 rosbag 파일이 기록된다. (ctrl+c로 기록을 종료할 수 있다.)
rosbag record -arosbag파일의 정보를 보여준다.
rosbag info <your bagfile>rosbag 파일을 재생한다.(기록된 메세지를 시간순서대로 퍼블리시한다.)
rosbag play <your bagfile>rosbag 파일을 2배속도로 재생한다.
rosbag play -r 2 <your bagfile>특정 메세지만 저장할 수 있다.(subset 파일에 저장된다.)
rosbag record -O subset /turtle1/cmd_vel /turtle1/pose참고자료 : http://wiki.ros.org/rosbag/Tutorials/Recording%20and%20playing%20back%20data
4. Custom plugins
그 외 유용한 RQT plugin
rosrun turtlesim turtlesim_noderosrun turtlesim turtle_teleop_keyrqtEasy Message Publisher : 현재 토픽 리스트에 올라온 토픽 메세지를 GUI상에서 메뉴얼로 퍼블리싱 가능하게 해준다.
Topic Monitor : 현재 토픽들의 값과 통신 속도를 실시간으로 모니터링 할 수 있다.
5. Own plugins
자신만의 GUI와 기능을 갖는 plugin을 개발해 RQT상에서 사용할 수 있다. 참고자료 : http://wiki.ros.org/rqt/Tutorials/Writing%20a%20Python%20Plugin
Rviz(ROS-visualization)
1. IMU 센서
2. Kinect
참고자료 : https://m.blog.naver.com/rmlee/221471760129 , 이상우님
3. Simulation
로봇의 오도메트리, TF, 센서 정보 등을 실시간 시각화를 통해 3D 시뮬레이션을 할 수 있다.
sudo apt-get install ros-kinetic-joy ros-kinetic-teleop-twist-joy ros-kinetic-teleop-twist-keyboard ros-kinetic-laser-proc ros-kinetic-rgbd-launch ros-kinetic-depthimage-to-laserscan ros-kinetic-rosserial-arduino ros-kinetic-rosserial-python ros-kinetic-rosserial-server ros-kinetic-rosserial-client ros-kinetic-rosserial-msgs ros-kinetic-amcl ros-kinetic-map-server ros-kinetic-move-base ros-kinetic-urdf ros-kinetic-xacro ros-kinetic-compressed-image-transport ros-kinetic-rqt-image-view ros-kinetic-gmapping ros-kinetic-navigation ros-kinetic-interactive-markerssudo apt-get install ros-melodic-joy ros-melodic-teleop-twist-joy ros-melodic-teleop-twist-keyboard ros-melodic-laser-proc ros-melodic-rgbd-launch ros-melodic-depthimage-to-laserscan ros-melodic-rosserial-arduino ros-melodic-rosserial-python ros-melodic-rosserial-server ros-melodic-rosserial-client ros-melodic-rosserial-msgs ros-melodic-amcl ros-melodic-map-server ros-melodic-move-base ros-melodic-urdf ros-melodic-xacro ros-melodic-compressed-image-transport ros-melodic-rqt-image-view ros-melodic-gmapping ros-melodic-navigation ros-melodic-interactive-markerscd ~/catkin_ws/src/git clone https://github.com/ROBOTIS-GIT/turtlebot3_msgs.gitgit clone https://github.com/ROBOTIS-GIT/turtlebot3.gitgit clone https://github.com/ROBOTIS-GIT/turtlebot3_simulations.gitcd ~/catkin_ws && catkin_makeRviz에 가상의 터틀봇3를 불러온다.
export TURTLEBOT3_MODEL=waffleroslaunch turtlebot3_fake turtlebot3_fake.launch터틀봇3 원격 조종 키 실행한다.
export TURTLEBOT3_MODEL=waffleroslaunch turtlebot3_teleop turtlebot3_teleop_key.launchrqt_graph터틀봇3의 노드 그래프
rosrun rqt_tf_tree rqt_tf_tree터틀봇3의 TF Tree
rostopic echo /odom터틀봇3의 오도메트리 실시간 정보
(원격 조종 키를 사용하면 오도메트리를 시각화해서 볼 수 있고 값을 rostopic echo를 통해 실시간으로 확인할 수 있다.)
4. SLAM(Simultaneous Localization And Mapping)
SLAM을 할 때 지도의 작성과정을 시각적으로 보여준다.
가상 환경 불러오기
export TURTLEBOT3_MODEL=waffleroslaunch turtlebot3_gazebo turtlebot3_world.launch터틀봇3 SLAM 실행
export TURTLEBOT3_MODEL=waffleroslaunch turtlebot3_slam turtlebot3_slam.launch터틀봇3 원격 조종 키
export TURTLEBOT3_MODEL=waffleroslaunch turtlebot3_teleop turtlebot3_teleop_key.launch
SLAM이 끝난 뒤 완성된 Map
Map 저장
rosrun map_server map_saver -f ~/map
저장된 Map
가상 내비게이션 with Gazebo
export TURTLEBOT3_MODEL=waffleroslaunch turtlebot3_gazebo turtlebot3_world.launch
- map 사
export TURTLEBOT3_MODEL=waffleroslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=$HOME/map.yaml
5. URDF
Unified Robot Description Format : ROS에서 사용되는 로봇 기술(Description) 형식 * URDF(Unified Robot Description Format) vs SDF(Simulation Description Format)
URDF는 하나의 robot 모델에 대해 기술하는 양식. 시뮬레이션 world 상에서 robot의 pose를 결정할 수 없다.
SDF는 world 상에서 여러개의 robot 모델에 대해 pose를 정의할 수 있으며 모델←→센서←→ World 의 관계에 대한 속성 정의도 가능하다.
쉽게 말해 서빙 로봇 서비스가 있는 매장에서 URDF는 서빙 로봇 하나의 도면!, SDF는 매장 전체 시스템의 도면!
1) URDF turtial 1 - URDF 이해하기
Link
link : 모델 상의 하나의 Body(바퀴, 링크, 실린더, 구 등)
visual : link 요소의 시각화 (.dae, .stl 지원)
collision : link 요소 간의 충돌을 확인하기 위한 geometry (.dae, .stl 지원)
inertial : link의 동적 속성 기술(질량, 관성 모멘트 등)
origin : link 모델 중심의 joint로부터의 위치
Joint
joint : link간의 구속관계 표현parent/child : link 간 구속관계에서 부모/자식 관계type : 관계의 종류(prismatic, revolute, continuous 등)axis : joint 축의 방향limit : joint의 이동가능 범위 제한origin : joint의 원점으로부터의 위치sensor : plugin을 통해 가상 world로부터의 센서 데이터를 취득material : link의 소재, 색상 등을 결정plugin : 모델을 제어하기 위한 controller 등 다른 플랫폼과 토픽/프레임을 공유하기 위한 수단
URDF 작성연습을 위해 시각화는 urdf_tutorial의 launch를 사용한다.
git clone https://github.com/ros/urdf_tutorial.giturdf_tutorial의 urdf 디렉토리에 다음 파일을 작성한다.
gedit mobile_robot.urdfURDF 기본구조
<?xml version="1.0"?>
<robot name="mobile_robot">
<material name="orange">
<color rgba="1 0.5 0.1 1"/>
</material>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<link name="base_link">
<visual>
<geometry>
<box size="1.5 0.6 0.3"/>
</geometry>
<material name="orange"/>
</visual>
</link>
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.125"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="white"/>
</visual>
</link> <joint name="base_to_caster_wheel" type="continuous"> <parent link="base_link"/> <child link="caster_wheel"/> <origin xyz="0.5 0 -0.275"/> <axis xyz="0 1 0"/> </joint> <link name="right_wheel"> <visual> <geometry> <cylinder length="0.2" radius="0.4"/> </geometry> <origin rpy="1.57075 0 0" xyz="0 0 0"/> <material name="white"/> </visual> </link> <joint name="base_to_right_wheel" type="continuous"> <parent link="base_link"/> <child link="right_wheel"/> <origin xyz="-0.3 -0.4 0"/> <axis xyz="0 -1 0"/> </joint> <link name="left_wheel"> <visual> <geometry> <cylinder length="0.2" radius ="0.4"/> </geometry> <origin rpy="1.57075 0 0" xyz="0 0 0"/> <material name="white"/> </visual> </link> <joint name="base_to_left_wheel" type="continuous"> <parent link="base_link"/> <child link="left_wheel"/> <origin xyz="-0.3 0.4 0"/> <axis xyz="0 1 0"/> </joint></robot>Rviz에 URDF로 작성한 모델을 시각화한다.
$ roslaunch urdf_tutorial display.launch model:=urdf/mobile_robot.urdf
URDF로 작성한 모바일 로봇 모델
Joint 컨트롤러
2) URDF tutotial 2 - 나의 모델 불러와 Rviz에 시각화하기
새로운 URDF 작성
$ gedit mobile_robot_stl.urdfstl파일 불러오는 URDF
<?xml version="1.0"?><robot name="mobile_robot_stl"> <material name="orange"> <color rgba="1 0.5 0.1 1"/> </material> <link name="base_link"> <visual> <origin rpy="1.57075 0 1.57075" xyz="0 0 0"/> <geometry> <mesh filename="package://urdf_tutorial/meshes/ros_test.stl" scale="0.01 0.01 0.01"/> </geometry> <material name="orange"/> </visual> </link></robot>예제 stl파일 가져오기(urdf 디렉토리에 저장)
$ wget -O ros_test.stl https://github.com/Denhanis/ROS-Study/blob/master/stl/ros_test.stl?raw=trueRviz로 시각화
$ roslaunch urdf_tutorial display.launch model:=urdf/mobile_robot_stl.urdf
3) URDF tutorial 3 - 3D모델에 물리적 특성 입히기
참고자료(관성 텐서 구하기) : https://en.wikipedia.org/wiki/List_of_moments_of_inertia#List_of_3D_inertia_tensors
물리적 특성(collision, inertial) 반영된 URDF
<?xml version="1.0"?><robot name="mobile_robot"> <material name="orange"> <color rgba="1 0.5 0.1 1"/> </material> <material name="white"> <color rgba="1 1 1 1"/> </material> <link name="base_link"> <visual> <geometry> <box size="1.5 0.6 0.3"/> </geometry> <material name="orange"/> </visual> <collision> <geometry> <box size="1.5 0.6 0.3"/> </geometry> </collision> <inertial> <mass value="10"/> <inertia ixx="0.375" ixy="0.0" ixz="0.0" iyy="1.95" iyz="0.0" izz="2.175"/> </inertial> </link> <link name="caster_wheel"> <visual> <geometry> <sphere radius="0.125"/> </geometry> <origin rpy="0 0 0" xyz="0 0 0"/> <material name="white"/> </visual> <collision> <geometry> <sphere radius="0.125"/> </geometry> </collision> <inertial> <mass value="3"/> <inertia ixx="0.01875" ixy="0.0" ixz="0.0" iyy="0.01875" iyz="0.0" izz="0.01875"/> </inertial> </link> <joint name="base_to_caster_wheel" type="continuous"> <parent link="base_link"/> <child link="caster_wheel"/> <origin xyz="0.5 0 -0.275"/> <axis xyz="0 1 0"/> </joint> <link name="right_wheel"> <visual> <geometry> <cylinder length="0.2" radius="0.4"/> </geometry> <origin rpy="1.57075 0 0" xyz="0 0 0"/> <material name="white"/> </visual> <collision> <geometry> <cylinder length="0.2" radius="0.4"/> </geometry> <origin rpy="1.57075 0 0" xyz="0 0 0"/> </collision> <inertial> <mass value="5"/> <inertia ixx="0.217" ixy="0.0" ixz="0.0" iyy="0.217" iyz="0.0" izz="0.4"/> </inertial> </link> <joint name="base_to_right_wheel" type="continuous"> <parent link="base_link"/> <child link="right_wheel"/> <origin xyz="-0.3 -0.4 0"/> <axis xyz="0 -1 0"/> </joint> <link name="left_wheel"> <visual> <geometry> <cylinder length="0.2" radius ="0.4"/> </geometry> <origin rpy="1.57075 0 0" xyz="0 0 0"/> <material name="white"/> </visual> <collision> <geometry> <cylinder length="0.2" radius="0.4"/> </geometry> <origin rpy="1.57075 0 0" xyz="0 0 0"/> </collision> <inertial> <mass value="5"/> <inertia ixx="0.217" ixy="0.0" ixz="0.0" iyy="0.217" iyz="0.0" izz="0.4"/> </inertial> </link> <joint name="base_to_left_wheel" type="continuous"> <parent link="base_link"/> <child link="left_wheel"/> <origin xyz="-0.3 0.4 0"/> <axis xyz="0 1 0"/> </joint></robot>Rviz로 시각화
$ roslaunch urdf_tutorial display.launch model:=urdf/mobile_robot.urdf
4) URDF tutorial 4 - URDF Check
URDF Check tool 다운로드
$ sudo apt-get install liburdfdom-toolsURDF 링크 정합성 체크
$ check_urdf mobile_robot.urdf
URDF 링크 관계정보
URDF 링크 관계정보 시각화
$ urdf_to_graphiz mobile_robot.urdf $ evince mobile_robot.pdf
URDF 링크 관계정보 pdf로 저장
URDF 링크 관계정보 시각화
5) URDF tutorial 4 - Xacro 이용하여 URDF 쉽게 작성하기
Xacro(XML Macro)를 사용한 URDF 작성
<?xml version="1.0"?><robot name="mobile_robot" xmlns:xacro="http://ros.org/wiki/xacro"> <xacro:property name="body_width" value="0.6" /> <xacro:property name="body_height" value="1.5" /> <xacro:property name="body_depth" value="0.3" /> <xacro:property name="caster_radius" value="0.125" /> <xacro:property name="wheel_radius" value="0.4" /> <xacro:property name="wheel_length" value="0.2" /> <xacro:property name="pi" value="3.1415" /> <xacro:macro name="default_inertial" params="mass"> <inertial> <mass value="${mass}" /> <inertia ixx="0.375" ixy="0.0" ixz="0.0" iyy="1.95" iyz="0.0" izz="2.175"/> </inertial> </xacro:macro> <xacro:macro name="y_axis_joint"> <axis xyz="0 1 0"/> </xacro:macro> <material name="orange"> <color rgba="1 0.5 0.1 1"/> </material> <material name="white"> <color rgba="1 1 1 1"/> </material> <link name="base_link"> <visual> <geometry> <box size="${body_height} ${body_width} ${body_depth}"/> </geometry> <material name="orange"/> </visual> <collision> <geometry> <box size="${body_height} ${body_width} ${body_depth}"/> </geometry> </collision> <xacro:default_inertial mass="10"/> </link> <link name="caster_wheel"> <visual> <geometry> <sphere radius="${caster_radius}"/> </geometry> <origin rpy="0 0 0" xyz="0 0 0"/> <material name="white"/> </visual> <collision> <geometry> <sphere radius="${caster_radius}"/> </geometry> </collision> <inertial> <mass value="3"/> <inertia ixx="0.01875" ixy="0.0" ixz="0.0" iyy="0.01875" iyz="0.0" izz="0.01875"/> </inertial> </link> <joint name="base_to_caster_wheel" type="continuous"> <parent link="base_link"/> <child link="caster_wheel"/> <origin xyz="0.5 0 -0.275"/> <xacro:y_axis_joint/> </joint> <xacro:macro name="wheel" params="prefix suffix mass reflect"> <link name="${prefix}_wheel"> <visual> <geometry> <cylinder length="${wheel_length}" radius="${wheel_radius}"/> </geometry> <origin rpy="${pi/2} 0 0" xyz="0 0 0"/> <material name="white"/> </visual> <collision> <geometry> <cylinder length="${wheel_length+0.1}" radius="${wheel_radius+0.1}"/> </geometry> <origin rpy="${pi/2} 0 0" xyz="0 0 0"/> </collision> <inertial> <mass value="${mass}"/> <inertia ixx="${mass*(3*wheel_radius*wheel_radius+wheel_length*wheel_length)/12}" ixy="0.0" ixz="0.0" iyy="${mass*(3*wheel_radius*wheel_radius+wheel_length*wheel_length)/12}" iyz="0.0" izz="${0.5*mass*wheel_radius*wheel_radius}"/> </inertial> </link> <joint name="${suffix}_to_${prefix}_wheel" type="continuous"> <parent link="${suffix}_link"/> <child link="${prefix}_wheel"/> <origin xyz="-0.3 ${0.4*reflect} 0"/> <xacro:y_axis_joint/> </joint> </xacro:macro> <xacro:wheel prefix="right" suffix="base" mass="5" reflect="-1"/> <xacro:wheel prefix="left" suffix="base" mass="5" reflect="1"/></robot>Xacro 실행하기 위해 반드시 추가해야하는 Command
<launch> <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" /> <param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" /> <param name="use_gui" value="$(arg gui)"/> <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" /> <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" /> <node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" /></launch>$ roslaunch urdf_tutorial display.launch model:=urdf/mobile_robot.urdf.xacro6. URDF tutorial 7 - SDF Converter
$ gz sdf --print my_urdf.urdf > my_sdf.sdf6. manipulator (TBU)
Gazebo
1. URDF로 만든 3D 모델 Gazebo에 불러오기
URDF를 Gazebo 환경으로 불러오기 위해선 다음과 같은 작업이 필요하다.1) Gazebo plugin 추가2) 몇 가지 추가 정보 URDF에 입력(joint limit, transmission 정보, 물리 계수)3) Controller configuration 작성4) Launch file 작성 1) Gazebo plugin 추가
URDF 마지막 부분에 다음의 gazebo plugin 추가
<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/</robotNamespace> </plugin> </gazebo>2) 몇 가지 추가 정보 URDF에 입력(joint limit, transmission 정보, 물리 계수)
joints 수정 및 transmission 추가
<joint name="head_swivel" type="continuous"> <parent link="base_link"/> <child link="head"/> <axis xyz="0 0 1"/> <origin xyz="0 0 ${bodylen/2}"/> <limit effort="30" velocity="1.0"/> </joint> <transmission name="head_swivel_trans"> <type>transmission_interface/SimpleTransmission</type> <actuator name="$head_swivel_motor"> <mechanicalReduction>1</mechanicalReduction> </actuator> <joint name="head_swivel"> <hardwareInterface>PositionJointInterface</hardwareInterface> </joint> </transmission> <gazebo reference="${prefix}_${suffix}_wheel"> <mu1 value="200.0"/> <mu2 value="100.0"/> <kp value="10000000.0" /> <kd value="1.0" /> <material>Gazebo/Grey</material> </gazebo>최종 수정된 URDF
3) Controller configuration 작성
urdf_tutorial 디렉토리에 config 디렉토리를 생성하여 controller config 문서 생성(.yaml)
$ mkdir config$ touch /config/joints.yaml$ touch /config/caster.yaml$ touch /config/diffdrive.yamljoints.yaml
type: "joint_state_controller/JointStateController"publish_rate: 50caster.yaml
type: "position_controllers/JointPositionController"joint: head_swiveldiffdrive.yaml
type: "diff_drive_controller/DiffDriveController" publish_rate: 50 left_wheel: ['left_front_wheel_joint', 'left_back_wheel_joint'] right_wheel: ['right_front_wheel_joint', 'right_back_wheel_joint'] wheel_separation: 0.44 # Odometry covariances for the encoder output of the robot. These values should # be tuned to your robot's sample odometry data, but these values are a good place # to start pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03] twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03] # Top level frame (link) of the robot description base_frame_id: base_link # Velocity and acceleration limits for the robot linear: x: has_velocity_limits : true max_velocity : 0.2 # m/s has_acceleration_limits: true max_acceleration : 0.6 # m/s^2 angular: z: has_velocity_limits : true max_velocity : 2.0 # rad/s has_acceleration_limits: true max_acceleration : 6.0 # rad/s^24) Launch file 작성
gazebo_launch를 이용하기 위해 해당 launch파일을 urdf_tutorial/launch로 가져오기
$ wget -O gazebo.launch https://github.com/ros/urdf_sim_tutorial/blob/master/launch/gazebo.launch?raw=true우리가 만든 모델을 Gazebo와 Rviz에서 사용하기 위한 launch 파일 작성
$ gedit mobile_robot.launchsudo apt install ros-kinetic-gazebo-ros-control2. SDF로 만든 3D 모델 Gazebo에 불러오기
https://github.com/modulabs/gazebo-tutorial/wiki/Make-a-Mobile-Robot SDF를 Gazebo 환경으로 불러오기 위해선 다음과 같은 작업이 필요하다.1) 모델 directory 설정2) 모델의 구조 생성3) Gazebo에서 모델 불러오기 1) 모델 directory 설정
모델 폴더를 생성
$ mkdir -p ~/.gazebo/models/my_robot모델 config 파일을 생성
$ gedit ~/.gazebo/models/my_robot/model.configconfig 파일에 다음 코드를 작성
<?xml version="1.0"?> <model> <name>My Robot</name> <version>1.0</version> <sdf version='1.4'>model.sdf</sdf> <author> <name>My Name</name> <email>me@my.email</email> </author> <description> My awesome robot. </description> </model>SDF 파일을 생성
$ gedit ~/.gazebo/models/my_robot/model.sdfSDF 파일에 다음 코드를 작성
<?xml version='1.0'?> <sdf version='1.4'> <model name="my_robot"> </model> </sdf>2) 모델의 구조 생성
SDF 파일을 실행
$ gedit ~/.gazebo/models/my_robot/model.sdf모델의 static을 설정
static이 true이면 물리엔진의 영향을 받지 않고 false이면 물리엔진의 영향을 받음
<?xml version='1.0'?> <sdf version='1.4'> <model name="my_robot"> <static>true</static> </model> </sdf>모델에 사각형 베이스 추가
<?xml version='1.0'?> <sdf version='1.4'> <model name="my_robot"> <static>true</static> <link name='chassis'> <pose>0 0 .1 0 0 0</pose> <collision name='collision'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </collision> <visual name='visual'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </visual> </link> </model> </sdf>모델에 구 형상의 바퀴 추가
<?xml version='1.0'?> <sdf version='1.4'> <model name="my_robot"> <static>true</static> <link name='chassis'> <pose>0 0 .1 0 0 0</pose> <collision name='collision'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </collision> <visual name='visual'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </visual> <collision name='caster_collision'> <pose>-0.15 0 -0.05 0 0 0</pose> <geometry> <sphere> <radius>.05</radius> </sphere> </geometry> <surface> <friction> <ode> <mu>0</mu> <mu2>0</mu2> <slip1>1.0</slip1> <slip2>1.0</slip2> </ode> </friction> </surface> </collision> <visual name='caster_visual'> <pose>-0.15 0 -0.05 0 0 0</pose> <geometry> <sphere> <radius>.05</radius> </sphere> </geometry> </visual> </link> </model> </sdf>모델에 왼쪽 바퀴 추가
<?xml version='1.0'?> <sdf version='1.4'> <model name="my_robot"> <static>true</static> <link name='chassis'> <pose>0 0 .1 0 0 0</pose> <collision name='collision'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </collision> <visual name='visual'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </visual> <collision name='caster_collision'> <pose>-0.15 0 -0.05 0 0 0</pose> <geometry> <sphere> <radius>.05</radius> </sphere> </geometry> <surface> <friction> <ode> <mu>0</mu> <mu2>0</mu2> <slip1>1.0</slip1> <slip2>1.0</slip2> </ode> </friction> </surface> </collision> <visual name='caster_visual'> <pose>-0.15 0 -0.05 0 0 0</pose> <geometry> <sphere> <radius>.05</radius> </sphere> </geometry> </visual> </link> <link name="left_wheel"> <pose>0.1 0.13 0.1 0 1.5707 1.5707</pose> <collision name="collision"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </collision> <visual name="visual"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </visual> </link> </model> </sdf>모델의 왼쪽 바퀴를 오른쪽으로 복사
<?xml version='1.0'?> <sdf version='1.4'> <model name="my_robot"> <static>true</static> <link name='chassis'> <pose>0 0 .1 0 0 0</pose> <collision name='collision'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </collision> <visual name='visual'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </visual> <collision name='caster_collision'> <pose>-0.15 0 -0.05 0 0 0</pose> <geometry> <sphere> <radius>.05</radius> </sphere> </geometry> <surface> <friction> <ode> <mu>0</mu> <mu2>0</mu2> <slip1>1.0</slip1> <slip2>1.0</slip2> </ode> </friction> </surface> </collision> <visual name='caster_visual'> <pose>-0.15 0 -0.05 0 0 0</pose> <geometry> <sphere> <radius>.05</radius> </sphere> </geometry> </visual> </link> <link name="left_wheel"> <pose>0.1 0.13 0.1 0 1.5707 1.5707</pose> <collision name="collision"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </collision> <visual name="visual"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </visual> </link> <link name="right_wheel"> <pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose> <collision name="collision"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </collision> <visual name="visual"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </visual> </link> </model> </sdf>static을 false로 설정, 왼쪽, 오른쪽 바퀴에 hinge 추가
<?xml version='1.0'?> <sdf version='1.4'> <model name="my_robot"> <static>false</static> <link name='chassis'> <pose>0 0 .1 0 0 0</pose> <collision name='collision'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </collision> <visual name='visual'> <geometry> <box> <size>.4 .2 .1</size> </box> </geometry> </visual> <collision name='caster_collision'> <pose>-0.15 0 -0.05 0 0 0</pose> <geometry> <sphere> <radius>.05</radius> </sphere> </geometry> <surface> <friction> <ode> <mu>0</mu> <mu2>0</mu2> <slip1>1.0</slip1> <slip2>1.0</slip2> </ode> </friction> </surface> </collision> <visual name='caster_visual'> <pose>-0.15 0 -0.05 0 0 0</pose> <geometry> <sphere> <radius>.05</radius> </sphere> </geometry> </visual> </link> <link name="left_wheel"> <pose>0.1 0.13 0.1 0 1.5707 1.5707</pose> <collision name="collision"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </collision> <visual name="visual"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </visual> </link> <link name="right_wheel"> <pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose> <collision name="collision"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </collision> <visual name="visual"> <geometry> <cylinder> <radius>.1</radius> <length>.05</length> </cylinder> </geometry> </visual> </link> <joint type="revolute" name="left_wheel_hinge"> <pose>0 0 -0.03 0 0 0</pose> <child>left_wheel</child> <parent>chassis</parent> <axis> <xyz>0 1 0</xyz> </axis> </joint> <joint type="revolute" name="right_wheel_hinge"> <pose>0 0 0.03 0 0 0</pose> <child>right_wheel</child> <parent>chassis</parent> <axis> <xyz>0 1 0</xyz> </axis> </joint> </model> </sdf>3) Gazebo에서 모델 불러오기
Gazebo 실행
$ gazebo모델 Insert
Gazebo 실행 후 GUI 인터페이스 왼쪽 상단의 Insert 탭 클릭
'My Robot' 모델 클릭
메인 화면에서 모델을 배치할 위치에 마우스를 위치시키고 클릭
모델 작동 테스트
화면 오른쪽 작은 점 3개 버튼을 클릭한 상태로 마우스를 왼쪽으로 이동시켜 Joints 탭 활성화
'left_wheel_hinge'와 'right_wheel_hinge'를 각각 0.1N 씩 포스 입력
모델이 움직이는 모습을 확인 할 수 있음
Last updated
Was this helpful?