-
Notifications
You must be signed in to change notification settings - Fork 14
Digital Elevation Models
디지털 고도 모델(DEM)은 지형표면에 대한 3D 표현입니다. 이 지형표면은 빌딩이나 초목들이 없는상태입니다. DEMS는 라이다,레이더,카메라같은 센서를 사용해서 만들어집니다. 지형고도는 같은 고도를 이은 선으로 샘플링 됩니다. Wikipedia는 DEMS와 관련한 더 상세한것들을 얻기위한 소스입니다. The term DEM is just a generic denomination, not a specific format. In fact, the DEMs can be represented as a grid of elevations (raster) or as a vector-based triangular irregular network (TIN). Currently, Gazebo only supports raster data in the supported formats available in GDAL.
DEMS를 가제보에서 사용하게된 동기는 실제의 지형에서 시물레이션을 할수있다는 점이다. 구조나 농업에 있어서, 그들의 로봇이 실네의 지형에서 테스팅되는것에 관심이 있을것 입니다.
DEM 화일을 사용하기 위해서는 GDAL 라이브러리를 설치해야 합니다.
$ sudo apt-get install gdal-bin libgdal-dev python-gdal
고도데이터를 제공하는 기관은 많이 있습니다. 예를들어, Mount St.helens (80년대 화산폭발 전후)DEM 화일을 다운로드 받으세요 이 화일들은 공개된 도메인이고,USGS에서 배포합니다.
압축을 푸시고 이름을 "mtsthelens.dem" 로 하세요~
$ cd ~/Downloads
$ wget https://bitbucket.org/osrf/gazebo_tutorials/raw/default/dem/files/mtsthelens_before.zip
$ unzip ~/Downloads/mtsthelens_before.zip -d /tmp
$ mv /tmp/30.1.1.1282760.dem /tmp/mtsthelens.dem
보통, DEM 화일은 큰 해상도를 갖고있습니다. 그래서 가제보로 다룰수 없습니다. 그래서 DE화일의 해상도를 최적화 하기위한 좋은 방법이 있습니다. 다음 명령어는 지형도를 129*129로 스케일링 합니다 또한 media/dem 디렉토리로 복사를 합니다.
$ mkdir -p /tmp/media/dem/
$ gdalwarp -ts 129 129 /tmp/mtsthelens.dem /tmp/media/dem/mtsthelens_129.dem
가제보안에서 DEM 화일은 Heightmap image를 로드하는 방법과 같은 방법으로 로드 됩니다. 가제보는 이 화일이 평면 이미지 또는 DEM 화일임을 자동으로 감지합니다. volcano.world 화일을 생성합니다. 그리고 다음 콘텐츠로 복사합니다. 당신이 원하는 곳으로 화일을 저장합니다.
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<model name="heightmap">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<heightmap>
<uri>file://media/dem/mtsthelens_129.dem</uri>
<size>150 150 50</size>
<pos>0 0 -685</pos>
</heightmap>
</geometry>
</collision>
<visual name="visual_abcedf">
<geometry>
<heightmap>
<texture>
<diffuse>file://media/materials/textures/dirt_diffusespecular.png</diffuse>
<normal>file://media/materials/textures/flat_normal.png</normal>
<size>1</size>
</texture>
<texture>
<diffuse>file://media/materials/textures/grass_diffusespecular.png</diffuse>
<normal>file://media/materials/textures/flat_normal.png</normal>
<size>1</size>
</texture>
<texture>
<diffuse>file://media/materials/textures/fungus_diffusespecular.png</diffuse>
<normal>file://media/materials/textures/flat_normal.png</normal>
<size>1</size>
</texture>
<blend>
<min_height>2</min_height>
<fade_dist>5</fade_dist>
</blend>
<blend>
<min_height>4</min_height>
<fade_dist>5</fade_dist>
</blend>
<uri>file://media/dem/mtsthelens_129.dem</uri>
<size>150 150 50</size>
<pos>0 0 -685</pos>
</heightmap>
</geometry>
</visual>
</link>
</model>
</world>
</sdf>
The element in the code above tells Gazebo whether to load the DEM with the original dimensions (when is not present) or to scale it (when is present). In case you prefer to scale the DEM, the element tells Gazebo the size in meters that the terrain will have in the simulation. If you want to maintain the correct aspect ratio, be sure to properly calculate its size in all three dimensions. In our example, the DEM will be scaled to a square of 150 x 150 meters and a height of 50 meters. The minimum elevation for this particular DEM file is 685 meters, so in the element, we translate the entire DEM in negative z direction so that it sits at z=0 in the world.
ekdtlsdml DEM화일을 포함한 WORLD를 런칭하세요 당신은 VOLCANO를 볼수있어야 합니다. 우리의 경우에는 이 화일은 /tmp 디렉토리에 있습니다.
# Be sure of sourcing gazebo setup.sh in your own installation path
$ source /usr/share/gazebo/setup.sh
$ GAZEBO_RESOURCE_PATH="$GAZEBO_RESOURCE_PATH:/tmp" gazebo /tmp/volcano.world
화산폭발 이후에 DEM 화일도 동일한 방법으로 로드 해 보세요 당신은 아래그림과 같은 heightmap을 가제보 안에서 얻을수 있어야 합니다.
다음,우리는 특정지역의 DEM 화일을 얻는 한가지 방법에 대해 기술을 할것입니다.
Global Land Cover Facility 는 높은 해상도의 디지털 사진그래픽 데이터 베이스(지구)를 유지관리하고 있습니다. 그것의 "Search and Preview tool"로 가세요, 당신은 아래와 비슷한 이미지를 보게될것입니다. 모든 지형PATH는 툴을 이용하기 전에 알고있어야할 유일한 고유의 PATH와 ROW를 갖습니다 우리는 관심지역의 PATH,ROW를 알기위해서 QGIS를 사용합니다.
QGIS는 교차플랫폼 오픈소스 지리학 정보 시스템 프로그램 입니다(데이타를 보고, 편집하고,해석) QGIS를 다음의 instructions detailed on the QGIS website .를 따라해서 다운을 받으세요
QGIS를 열고, 좌측 칼럼 아이콘 "WMS/WMTS layer"를 클릭하세요 default servers 를 클릭하세요 Lizardtech server를 선택하세요 그리고 CONNECT를 누르세요 그리고 MODIS를 선택하고 ADD를 누르세요 팝업윈도우를 닫습니다. 다음 스텝은 다른 가능한 PATH 로 다른 LAYER를 추가하세요 this shapefile 를 다운로드 하고, 압축을 푸세요 QGIS로 되돌아가서 Add Vector Layer 를 누르세요 Browse를 클릭하고, 당신의 앞의 압축푼 wrs2descending.shp file. 을 선택하세요 윈도우에서 오픈을 누릅니다 이제 당신은 MAIN WINDOWDP E두 LAYER를 보게될것입니다. wrs2descending layer의 투명도를 변경하세요(두 LAYER를 동시에 볼수있도록) on wrs2_descending layer,를 더블클릭하세요 그리고 그것의 투명도를 수정하세요(약 85%)
스크롤, 좌측 버튼을 이용해서 관심지역으로 이동이 가능합니다. 상단 BAR의 the icon labeled Identify Features를 클릭합니다. 당신의 관심지역을 클릭하고, 그지역의 모든 지형패치가 하일라이트 됩니다. 새로운 팝업윈도우가 하이라이트된 패치마다 PATH/ROW를 보여줍니다. 당신이 PATH,ROW(DEM PATCH:LAS Palmas를 포함한)를 볼수있있습니다
GLCF 서치툴을 가진 당신의 브로우져로 되돌아 가세요 그리고 PATH/ROW를 밸류를 Start Path and Start Row에 입력하세요 그다음 Submit Query를 누르세요 결과를 보기위해 Preview and Download를 누르세요 당신의 지역의 화일을 선택하고 다운로드를 누르세요 마지막으로 당신의 화일( .GZ)를 선택하고, 그것을 좋아하는 폴더에 압축을 풀어놓습니다. Global Land Cover Facility files 은 GeoTiff format, 입니다. 가장 일반적인 DEM화일 FORMAT 입니다
DEM data는 보통 매우높은 해상도를 갖습니다. 가제보에서 사용할수있을정도의 수준으로 해상도를 줄이기 위해 gdalwarp를 사용합니다.
$ gdalwarp -ts <width> <height> <srcDEM> <targetDEM>
DEM DATA는 종종 "holes" or "void" 지역을 포함합니다. 이 섹션은 DEM화일 생성중에 데이타가 수집되지 않은 지역과 연관이 있습니다. HOLE CASE의 경우에, THE HOLE은 DEM안에 사용되는 데이타 타입중에서 최대 또는 최소수치에 해당이 됩니다.
항상 DEM화일 최종버전을 다운 받으세요 HOLES들은 채워집니다. 수작업으로 수정도 시도하세요 ,gdal tools ,gdal_fillnodata.py. 를 이용합니다.
가제보가을 직접적으로 DEM을 지원하지는 않치만, GDAL은 DEMS 셋을 하나로 합치기 위한 유틸리티 셋을 가지고 있습니다. 첫번째로 합치기를 원하는 DEMS 셋을 다운로드 합니다. 패치는 다른것에 오버랩 되어있습니다,GDAL은 그들을 균일하게 합칠것입니다. 당신의 현재 디렉토리가 합쳐질 준비가 된 Geotiff files를 포함하고 있다면, 다음 명령어를 수행하세요
$ gdal_merge.py *.tif -o dem_merged.tif
이제 당신은 dem_merged.tif를 당신의 WORLD FILE안에서 사용할수있습니다. 가제보는 영역을 모든 합쳐진 패치와 함께 로드할것입니다.
다음 스크린삿에서 당신은 4가지 지역이 합쳐진 결과를 볼수가 있습니다.
-
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]