-
Notifications
You must be signed in to change notification settings - Fork 14
Create a Video with a Camera
이번 튜토리얼은 gazebo world에서 카메라 센서로부터 비디오를 만드는 방법을 보인다.
Gazebo는 카메라 이미지를 디스크에 자동적으로 저장이 가능하다.
이를 위해, <save>
tag가 camera sensor에 반드시 추가되어야 한다.
this world를 다운로드하고 camera_tutorial.world
로 저장한다.
<?xml version="1.0"?>
<sdf version='1.6'>
<world name='default'>
<model name='unit_box'>
<pose>0 0 2.5 0 -0 0</pose>
<link name='link'>
<visual name='visual'>
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
</link>
</model>
<light name='user_directional_light_0' type='directional'>
<pose>0 0 1 0 0 0</pose>
</light>
<model name='camera'>
<static>true</static>
<pose>-1 0 2 0 1 0</pose>
<link name='link'>
<visual name='visual'>
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name='my_camera' type='camera'>
<camera>
<save enabled="true">
<path>/tmp/camera_save_tutorial</path>
</save>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
</sensor>
</link>
</model>
</world>
</sdf>
중요한 부분은 다음과 같다.
<sensor name="my_camera">
<camera>
<image>
<width>1920</width>
<height>1080</height>
</image>
...
<save enabled="true">
<path>/tmp/camera_save_tutorial</path>
</save>
...
<update_rate>30</update_rate>
</camera>
</sensor>
<save>
tag는 enabled
라는 특성이 있는데, 이는 반드시 저장되어야할 이미지를 위해 true
로 설정되어야 한다. child tag <path>
는 카메라 이미지가 저장되는 폴더이다. 만약 폴더가 존재하지 않는다면, gazebo에서 이를 만들것이다. <width>
and <height>
는 이미지의 resolution을 설정한다. update_rate
는 일초에 저장되는 이미지 파일의 수를 말한다. 이 카메라는 1초에 30프레임, 1920x1080 resolution를 갖는 이미지를 출력한다.
world파일을 다운로드 받은 폴더로 이동하고, 아래 명령어를 이용해 가제보를 실행한다.
gazebo --verbose camera_tutorial.world
몇초가 지난 후 Gazebo를 닫는다.
위 World는 /tmp/camera_save_tutorial
주소로 이미지를 저장할 것이다.
/tmp/camera_save_tutorials
폴더안에, 많은 이미지가 순서대로 있을 것이다. 그 사진들은 같은 resolution(1920x1080)를 갖는다. 처음 이미지는 default_camera_link_my_camera(1)-0000.jpg
를 가르킨다.
지금부터는 디스크에 저장된 카메라 이미지를 ffmpeg를 이용해 비디오로 변환할 수 있다.
이 command는 30 frames를 갖는 my_camera.mp4
라는 이름으로 비디오를 생성한다.
ffmpeg -r 30 -pattern_type glob -i '/tmp/camera_save_tutorial/default_camera_link_my_camera*.jpg' -c:v libx264 my_camera.mp4
만약 당신이 Ubuntu Trusty or a newer version를 갖고 있다면, 당신은 ffmpeg
대신에 avconv
를 갖고 있어야 할것이다.
(here is some of the backstory).
avconv
를 이용하기 위핸 Command는 다음과 같다:
avconv -framerate 30 -i /tmp/camera_save_tutorial/default_camera_link_my_camera\(1\)-%04d.jpg -c:v libx264 my_camera.mp4
비디오 다운로드 here.
-
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]