-
Notifications
You must be signed in to change notification settings - Fork 14
Visual Lightmap
라이트 맵은 일반적으로 복잡한 장면의 렌더링 성능을 향상시키는 데 사용됩니다. 라이트 맵은 조명 정보가 텍스처에 미리 구워진 텍스처 맵으로 생각할 수 있습니다. 결과 모델은 마치 환경의 조명으로 음영 처리 된 것처럼 보입니다. 조명이 미리 계산되므로 라이트 맵은 장면의 조명 포즈와 관련하여 움직이지 않는 모델에 적합합니다. 예를 들어, 건물, 가구,지면 및 지형이 방향성을 지닌 환경에서 정적 인 경우.
라이트 맵은 널리 사용되는 3D 모델링 도구를 사용하여 만들 수 있습니다. 예 : 믹서기. 이 튜토리얼에서는 메쉬와 미리 생성 된 라이트 맵을 제공하여 시간을 절약 할 것입니다.
Gazebo에서는 라이트 맵이 모형의 시각에 적용됩니다.
먼저 테이블 모델을 만듭니다. 모델은 아직 라이트 맵을 사용하지 않습니다.
mkdir -p ~/.gazebo/models/my_lightmap_table
Download the mesh and texture files.
mkdir -p ~/.gazebo/models/my_lightmap_table/meshes
cd ~/.gazebo/models/my_lightmap_table/meshes
wget http://gazebosim.org/models/table_marble/meshes/table_lightmap.dae
mkdir -p ~/.gazebo/models/my_lightmap_table/materials/scripts
mkdir -p ~/.gazebo/models/my_lightmap_table/materials/textures
cd ~/.gazebo/models/my_lightmap_table/materials/textures
wget http://gazebosim.org/models/table_marble/materials/textures/marble.png
wget http://gazebosim.org/models/table_marble/materials/textures/table_lightmap.png
Create a material script that will be used by the table model:
gedit ~/.gazebo/models/my_lightmap_table/materials/scripts/table_lightmap.material
Paste the following contents:
material Table/Marble_Lightmap
{
technique
{
pass
{
texture_unit
{
texture marble.png
}
}
}
}
Create a model.config file:
gedit ~/.gazebo/models/my_lightmap_table/model.config
Paste the following contents:
<?xml version="1.0"?>
<model>
<name>Lightmap Table</name>
<version>1.0</version>
<sdf version="1.5">model.sdf</sdf>
<author>
<name>Joe</name>
<email>[email protected]</email>
</author>
<description>
A table with lightmap.
</description>
</model>
Create a model.sdf file
gedit ~/.gazebo/models/my_lightmap_table/model.sdf
Paste the following:
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="my_lightmap_table">
<static>true</static>
<pose>0 0 0.648 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<mesh>
<uri>model:///my_lightmap_table/meshes/table_lightmap.dae</uri>
<scale>0.25 0.25 0.25</scale>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://my_lightmap_table/meshes/table_lightmap.dae</uri>
<scale>0.25 0.25 0.25</scale>
</mesh>
</geometry>
<material>
<script>
<uri>model://my_lightmap_table/materials/scripts</uri>
<uri>model://my_lightmap_table/materials/textures</uri>
<name>Table/Marble_Lightmap</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>
Run gazebo:
gazebo
Insert the Lightmap Table model into the scene:
이전에주의를 기울 였다면 아직 table_lightmap.png를 사용하지 않았다는 것을 알 수 있습니다. 적용 할 라이트 맵입니다. 그러나 먼저, Gazebo에게 lightmaps를 사용하기를 원하기 때문에 다이내믹 라이팅을 모델에 적용해서는 안된다고 설명해야합니다.
Edit the model.sdf file:
gedit ~/.gazebo/models/my_lightmap_table/model.sdf
Locate the material SDF element in the model.sdf and set lighting to be false
<material>
<script>
<uri>model://my_lightmap_table/materials/scripts</uri>
<uri>model://my_lightmap_table/materials/textures</uri>
<name>Table/Marble_Lightmap</name>
</script>
<lighting>false</lighting>
</material>
If you insert my_lightmap_table into the scene again, you should notice that the model now only has a texture but is no longer shaded.
Then tell the material script to blend the lightmap with the existing texture.
gedit ~/.gazebo/models/my_lightmap_table/materials/scripts/table_lightmap.material
Add a texture_unit that uses the table_lightmap.png texture
material Table/Marble_Lightmap
{
technique
{
pass
{
texture_unit
{
texture marble.png
}
texture_unit
{
texture table_lightmap.png
}
}
}
}
Finally, relaunch Gazebo and insert the table model:
-
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]