-
Notifications
You must be signed in to change notification settings - Fork 14
Attach Gripper to Robot
Make a Mobile Robot tutorial 에서 간단한 mobile robot을 만들었었다. 이 모델을 좀 더 크게 키워서 바로 직전에 만들었던 gripper를 붙여보자. 다시 말해서 모델을 assemble하여 새로운 모델을 손쉽게 만드는 법을 배워보자.
일단 Mobile Robot 파일은 좀 더 크게 수정한다.
다음으로 base와 gripper를 조립할 manipulator 모델을 생성한다. 모델 폴더를 생성하고,
$ mkdir ~/.gazebo/models/simple_mobile_manipulator
$ gedit ~/.gazebo/models/simple_mobile_manipulator/model.config
model.config 파일은 기존과 비슷하게 생성한다.
<?xml version="1.0"?>
<model>
<name>Simple Mobile Manipulator</name>
<version>1.0</version>
<sdf version='1.5'>manipulator.sdf</sdf>
<author>
<name>My Name</name>
<email>[email protected]</email>
</author>
<description>
My simple mobile manipulator
</description>
</model>
다음으로 manipulator SDF 파일을 생성한다.
$ gedit ~/.gazebo/models/simple_mobile_manipulator/manipulator.sdf
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="simple_mobile_manipulator">
<include>
<uri>model://my_gripper</uri>
<pose>1.3 0 0.1 0 0 0</pose>
</include>
<include>
<uri>model://simple_mobile_base_2</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<joint name="arm_gripper_joint" type="fixed">
<parent>mobile_base_2::chassis</parent>
<child>simple_gripper::riser</child>
</joint>
<!-- attach sensor to the gripper -->
<include>
<uri>model://hokuyo</uri>
<pose>1.3 0 0.3 0 0 0</pose>
</include>
<joint name="hokuyo_joint" type="fixed">
<child>hokuyo::link</child>
<parent>simple_gripper::palm</parent>
</joint>
</model>
</sdf>
이 때, 유의할 점은 각 노드에 삽입되는 모델 이름인데 include
, uri
노드에 'model://~'
부분은 각 모델 디렉토리 이름을, joint 노드에 링크로 들어가는 이름은 *.sdf 파일에 기재된 모델 이름이다. 모델 간의 관계는 include, pose 노드에 static하게 기술되고 노드에서는 child, parent가 어떤 링크인지만 기재된다.
참고로, gripper palm에 hokuyo 센서도 부착하였는데, 원래는 hokuyo 모델은 없으면 자동으로 download가 되지만 자동으로 잘 되지 않을 때는 수동으로 받아야 한다.
$ cd ~/.gazebo/models
$ wget -q -R *index.html*,*.tar.gz --no-parent -r -x -nH http://models.gazebosim.org/hokuyo/
또는 Connecting to model database...
를 클릭하고 기다려보자
-
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]