-
Notifications
You must be signed in to change notification settings - Fork 14
Make a Simple Gripper
Gazebo 설치하면 home 폴더에 ~/.gazebo/models 폴더가 생성되는데 여기에 모델 파일들이 관리된다. (Model Database documentation과 SDF를 참조)
이전처럼 Gazebo를 바로 실행해서 모델들을 Insert할 수 있지만 *.world 파일을 이용하면 처음부터 원하는 모델을을 Insert한 채로 Gazebo를 실행할 수 있다. 다음은 gripper.world 파일 예시다.
world 파일을 위한 디렉토리 생성
$ mkdir -p ~/.gazebo/simple_gripper_tutorial
world 파일 생성
$ gedit ~/.gazebo/simple_gripper_tutorial/gripper.world
<?xml version="1.0"?>
<sdf version="1.4">
<world name="default">
<!-- A ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://my_gripper</uri>
</include>
</world>
</sdf>
world에서 ground_plane, sun, my_gripper 모델을 불러들이고 있다. 참고로 'model://' 다음에 오는 이름은 model.config 파일과 *.sdf 파일들이 생성되는 디렉토리 이름이다.
먼저 모델 파일 생성을 위해서 ~/.gazebo/models에 해당 디렉토리를 생성한다.
$ mkdir -p ~/.gazebo/models/my_gripper
$ cd ~/.gazebo/models/my_gripper
Gripper 모델 파일은 model.config, simple_gripper.sdf 두 개를 생성한다. (model.config 파일은 이름을 임의로 지을 수 없다!)
$ gedit ~/.gazebo/models/my_gripper/model.config
<?xml version="1.0"?>
<model>
<name>My Gripper</name>
<version>1.0</version>
<sdf version='1.4'>simple_gripper.sdf</sdf>
<author>
<name>My Name</name>
<email>[email protected]</email>
</author>
<description>
My awesome robot.
</description>
</model>
$ gedit ~/.gazebo/models/my_gripper/simple_gripper.sdf
<?xml version="1.0"?>
<sdf version="1.4">
<model name="simple_gripper">
<link name="riser">
<pose>-0.15 0.0 0.5 0 0 0</pose>
<inertial>
<pose>0 0 -0.5 0 0 0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>10.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.2 0.2 1.0</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.2 0.2 1.0</size>
</box>
</geometry>
<material>
<script>Gazebo/Purple</script>
</material>
</visual>
</link>
<link name="palm">
<pose>0.0 0.0 0.05 0 0 0</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.5</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Red</script>
</material>
</visual>
</link>
<link name="left_finger">
<pose>0.1 0.2 0.05 0 0 -0.78539</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.3 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.3 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Blue</script>
</material>
</visual>
</link>
<link name="left_finger_tip">
<pose>0.336 0.3 0.05 0 0 1.5707</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Blue</script>
</material>
</visual>
</link>
<link name="right_finger">
<pose>0.1 -0.2 0.05 0 0 .78539</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.3 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.3 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Green</script>
</material>
</visual>
</link>
<link name="right_finger_tip">
<pose>0.336 -0.3 0.05 0 0 1.5707</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Green</script>
</material>
</visual>
</link>
<static>false</static>
<joint name="palm_left_finger" type="revolute">
<pose>0 -0.15 0 0 0 0</pose>
<child>left_finger</child>
<parent>palm</parent>
<axis>
<limit>
<lower>-0.4</lower>
<upper>0.4</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="left_finger_tip" type="revolute">
<pose>0 0.1 0 0 0 0</pose>
<child>left_finger_tip</child>
<parent>left_finger</parent>
<axis>
<limit>
<lower>-0.4</lower>
<upper>0.4</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="palm_right_finger" type="revolute">
<pose>0 0.15 0 0 0 0</pose>
<child>right_finger</child>
<parent>palm</parent>
<axis>
<limit>
<lower>-0.4</lower>
<upper>0.4</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="right_finger_tip" type="revolute">
<pose>0 0.1 0 0 0 0</pose>
<child>right_finger_tip</child>
<parent>right_finger</parent>
<axis>
<limit>
<lower>-0.4</lower>
<upper>0.4</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="palm_riser" type="prismatic">
<child>palm</child>
<parent>riser</parent>
<axis>
<limit>
<lower>0</lower>
<upper>0.9</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
</model>
</sdf>
model.config와 simple_gripper.sdf 파일에 대한 설명은 생략한다.
다음으로 world 파일을 실행한다.
$ gazebo ~/.gazebo/simple_gripper_tutorial/gripper.world
설명한대로 ground_plane, simple_gripper 가 기본으로 Insert되어 있는 Gazebo 화면을 볼 수 있다.
모델에 우클릭을 하고 View
->Joints
와 View
->Wireframe
을 선택해주면 조인트가 좌표계로 디스플레이 되는 것을 볼 수 있다.
또한 모델의 조인트에 힘을 가해볼 수 있는데 오른쪽 가운데 표시된 핸들을 왼쪽으로 드래그 하면 Joints 탭이 생긴다. 그 다음 모델을 클릭해주면 Force, Position, Velocity 탭에서 각 조인트들에 힘이나 위치, 속도 등을 가해볼 수 있다.
-
Robot Simulators
-
Build a Robot
- Model structure and requirements
- How to contribute a model
- Make a model
- Make a Mobile Robot
- The relationship among Link, Joint and Axis
- Import Meshes
- Attach Meshes
- Add a Sensor to a Robot
- Make a Simple Gripper
- Attach Gripper to Robot
- Nested model
- Model Editor
- Animated Box
- Make an animated model(actor)
- Inertial parameters of triangle meshes
- Visibility layers
-
Model Editor
-
Build a World
-
Tools and utilities
-
Write a plugin
-
Plugins
-
Sensors
-
User input
-
Transport Library
-
Rendering Library
-
Connect to ROS
-
Ros Control - Advanced
-
DRCSIM for ROS Kinetic (Ubuntu16.04)
-
DRCSIM
- DRC Simulator installation
- Launchfile options
- Spawn Atlas into a custom world
- Animate joints
- Atlas Keyboard Teleoperation over ROS
- Teleoperate atlas with a music mixer
- Visualization and logging
- Atlas MultiSense SL head
- How to use the Atlas Sim Interface
- Atlas fake walking
- Grasp with Sandia hands
- DRC vehicle tele-operation
- DRC vehicle tele operation with Atlas
- Sending joint commands with ROS
- Atlas control over ROS with python
- Modify environment
- Atlas switching control modes
- Atlas Controller Synchronization over ROS Topics
- Changing Viscous Damping Coefficients Over ROS Service
- Running BDI controller demo
- Using the RobotiQ 3 Finger Adaptive Robot Gripper
- BDI Atlas Robot Interface 3.0.0 Stand In Example
-
HAPTIX
- HAPTIX software install and update
- HAPTIX C API
- HAPTIX Matlab and Octave API
- HAPTIX Simulation World API
- HAPTIX Teleoperation
- HAPTIX environment setup
- HAPTIX Optitrack Control
- HAPTIX Tactor Glove
- HAPTIX Simulation World API with Custom World Example
- HAPTIX logging
- HAPTIX DEKA Luke hand installation
- HAPTIX Simulation Scoring Plugin Example
-
MoveIt!
-
Rviz & rqt & ROSBAG
- Control Theory
- TroubleShooting
- Solidworks model to URDF
- ROS-Gazebo with MATLab
- MATLab installation in Linux
- [Gazebo simulation with MATLab]