티스토리 뷰
1. ex_urdf 패키지
ex_urdf 패키지 생성
catkin_create_pkg ex_urdf roscpp tf geometry_msgs urdf rviz xacro
2. urdf 파일
urdf 폴더 생성 후 pan_tilt.urdf 작성
<?xml version="1.0"?>
<robot name="ex_urdf_pan_tilt">
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.01" radius="0.2"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="yellow">
<color rgba="1 1 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.03" radius="0.2"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="pan_joint" type="revolute">
<parent link="base_link"/>
<child link="pan_link"/>
<origin xyz="0 0 0.1"/>
<axis xyz="0 0 1" />
<limit effort="300" velocity="0.1" lower="-3.14" upper="3.14"/>
<dynamics damping="50" friction="1"/>
</joint>
<link name="pan_link">
<visual>
<geometry>
<cylinder length="0.4" radius="0.04"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.09"/>
<material name="red">
<color rgba="0 0 1 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.4" radius="0.06"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.09"/>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="tilt_joint" type="revolute">
<parent link="pan_link"/>
<child link="tilt_link"/>
<origin xyz="0 0 0.2"/>
<axis xyz="0 1 0" />
<limit effort="300" velocity="0.1" lower="-4.71239" upper="-1.570796"/>
<dynamics damping="50" friction="1"/>
</joint>
<link name="tilt_link">
<visual>
<geometry>
<cylinder length="0.4" radius="0.04"/>
</geometry>
<origin rpy="0 1.570796 0" xyz="0 0 0"/>
<material name="green">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.4" radius="0.06"/>
</geometry>
<origin rpy="0 1.570796 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
</robot>
3. launch 파일
launch폴더 생성 후 view_pan_tilt_urdf.launch 파일 작성
<launch>
<arg name="model" />
<param name="robot_description" textfile="$(find ex_urdf)/urdf/pan_tilt.urdf" />
<!-- Setting gui parameter to true for display joint slider -->
<param name="use_gui" value="true"/>
<!-- Starting Joint state publisher node which will publish the joint values -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<!-- Starting robot state publish which will publish tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<!-- Launch visualization in rviz -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find ex_urdf)/urdf.rviz" required="True" />
</launch>
4. 빌드 및 파일 확인
빌드
cm
생성한 urdf파일에 문법적인 오류가 있는지 확인
check_urdf pan_tilt.urdf
이렇게 나오면 오류가 없는 것이다.
link와 joint관계도 pdf파일로 저장
urdf_to_graphiz pan_tilt.urdf
pdf파일을 열어서 확인하면 아래와 같다.
5. joint-state-publisher-gui 패키지 설치
sudo apt update
sudo apt install ros-kinetic-joint-state-publisher-gui
6. RVIZ 실행
roslaunch ex_urdf view_pan_tilt_urdf.launch
명령어를 실행하면 RVIZ에서 에러도 발생하고 화면에 아무것도 나타나지 않는다.
7. RVIZ 세팅
1) Displays - Fixed Frame에서
map → base_link로 변경
2) Add버튼
By display type에서 RobotModel과 TF추가
결과 화면
joint_state_publisher창은 RVIZ창에 가려서 안보일 수 있다.
클릭해주면 앞으로 나옴.
스크롤바로 pan_joint값과 tilt_joint값을 변경하면서 모델이 어떻게 변하는지 살펴본다.
8. RVIZ 설정 내용 저장
종료버튼을 누르면 저장할 것인지 물어본다.
Save 버튼 눌러서 저장!
'ROS' 카테고리의 다른 글
Ubuntu16.04 ROS Kinetic - rviz_xycar 패키지 : RVIZ기반 자동차 8자주행 예제. rviz_8_drive.py (0) | 2021.01.25 |
---|---|
Ubuntu16.04 ROS Kinetic - rviz_xycar 패키지 : RVIZ기반 자동차 바퀴 굴러가는 예제. move_joint.py (0) | 2021.01.24 |
Ubuntu16.04 ROS Kinetic - 저장된 ROS bag 파일에서 특정 토픽만 꺼내 동영상파일로 저장하기 (0) | 2021.01.19 |
Ubuntu16.04 ROS Kinetic - my_cam 패키지 (0) | 2021.01.19 |
Ubuntu16.04 ROS Kinetic - 초음파센서(HC-SR04) 4개 연결 실습 (0) | 2021.01.18 |
댓글
공지사항
최근에 올라온 글
최근에 달린 댓글
- Total
- Today
- Yesterday
링크
TAG
- 우분투
- Mount
- subscriber
- umount
- 프로그래머스
- 백준알고리즘
- python3
- Ubuntu16.04
- set backspace
- 아두이노 IDE
- C++
- 원격 통신
- vue/cli
- Python
- 초음파센서
- VMware
- 8자주행
- Ubuntu20.04
- 윈도우 복구
- roslaunch
- ROS
- VirtualBox
- 리눅스
- filesystem
- 윈도우
- sensehat
- Publisher
- 포트인식문제
- 코드리뷰
- HC-SR04
일 | 월 | 화 | 수 | 목 | 금 | 토 |
---|---|---|---|---|---|---|
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 |
글 보관함