-
Notifications
You must be signed in to change notification settings - Fork 14
Add a Sensor to a Robot
전제조건: Attach a Mesh as Visual
이번 튜토리얼은 어떻게 유저가 가제보 모델 데이터베이스내의 모델들로 부터 합성 모델들을 만들 수 있는지에 대해 설명한다. 이때 합성 모델의 다른 요소들을 연결하기 위해 <include>와 <joint>를 이용한다.
로봇이나 모델에 레이저를 추가하는 것은 단순히 모델에 센서를 포함하기만 하면 된다.
-
이전 튜토리얼에서 모델 폴더로 이동 하여라.
$ cd ~/.gazebo/models/my_robot
-
model.sdf 파일을 열어라.
-
파일의 마지막 근처 tag에 다음을 추가하여라.
<include>
<uri>model://hokuyo</uri>
<pose>0.2 0 0.2 0 0 0</pose>
</include>
<joint name="hokuyo_joint" type="fixed">
<child>hokuyo::link</child>
<parent>chassis</parent>
</joint>
<include> 블락은 가제보에게 모델을 찾고 그것을 부모 모델에 주어진 <pose>의 상태적인 위치에 삽입 하라고 알려준다. 이번 경우에는 우리는 hokuyo 레이저를 로봇의 앞쪽 위에 위치시킨다. <uri> 블락은 가제보에게 그것의 모델 데이터베이스 내에서 어디에서 모델을 찾을지를 알려준다. 새로운 <joint>는 로봇의 샤시위에 삽입된 hokuyo 레이저를 연결 시킨다. joint는 레이저가 움직이지 않도록 fixed 이다. joint 안에 <child> 이름은 hokuyo 모델의 SDF로 부터 정의된다. SDF는 다음과 같이 시작한다.
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="hokuyo">
<link name="link">
hokuyo 모델이 삽입될 때 hokyuo의 링크들은 그들의 모델 이름으로 네임스페이스 된다. 모델의 이름이 hokuyo인 경우 hokuyo 모델내에 각 링크는 hokuyo:: 가 앞에 붙는다.
- 이제 가제보를 시작하자 그리고 GUI의 Insert 탭을 사용하여 시뮬레이션에 로봇을 추가하여라. 만약 hokuyo 모델이 없다면 모델을 내려 받아야 한다.
$ cd ~/.gazebo/models <br/>
$ wget -q -R *index.html*,*.tar.gz --no-parent -r -x -nH http://models.gazebosim.org/hokuyo/
또는 Insert 탭 아래 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]