-
Notifications
You must be signed in to change notification settings - Fork 14
Import Meshes
이번 튜토리얼은 가제보에 3D mesh를 불러오는 방법을 설명한다.
가제보는 오른손 좌표 시스템을 사용한다. +Z는 위, +X는 스크린 안쪽, +Y는 왼쪽이다.
Reduce Complexity
많은 mesh들은 상당히 복잡할 수 있다. 수많은 삼각형들을 가진 mesh는 감소 되어야 하고, 효율적으로 각각의 mesh들로 분리 되어야 한다. 삼각형들을 줄이고 mesh를 분리하기 위해 관련된 정보들은 당신의 3D mesh 에디터의 문서를 보아라.
Center the mesh
첫 스텝에서 (0,0,0)에서 mesh의 센터이고, x축이 정면의 방향이다.
Scale the mesh
가제보는 metric system을 사용한다. 많은 mesh들은 English unit을 사용한다. mesh를 metric size로 스케일 할 수 있는 3D 에디터를 사용해라.
일단 mesh가 적절히 준비된다면, 그것을 Collada 파일로 내보내라. 이 포맷은 모든 3D정보와 물질 정보를 포함 할 것이다.
mesh를 테스트하는 가장 쉬운 방법은 단순한 world 파일 my_mesh.world을 만드는 것이다. 이 파일은 mesh를 로드 한다. my_mesh.dae를 실제 mesh의 파일 이름으로 대체 해라.
<?xml version="1.0"?>
<sdf version="1.4">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="my_mesh">
<pose>0 0 0 0 0 0</pose>
<static>true</static>
<link name="body">
<visual name="visual">
<geometry>
<mesh><uri>file://my_mesh.dae</uri></mesh>
</geometry>
</visual>
</link>
</model>
</world>
</sdf>
그리고나서 파일이 있는 폴더에서 가제보를 시작해라.
$ gazebo my_mesh.world
당신은 duck.dae, duck.png mesh 파일들을 이용 할 수 있다. 이것들을 world파일로서 같은 폴더에 함께 나두어라. duck mesh는 위쪽 방향을 y축으로 정의해 놓았기 때문에 당신은 그것을 위쪽 방향으로 보이기 위해서는 sdf에서 회전을 주어야 한다.
-
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]