Create a Video with a Camera


Introduction

This tutorial shows how to create a video from a camera sensor in a gazebo world.

Save Camera Images

Gazebo can automatically save camera images to disk. To do so, a <save> tag must be added to a camera sensor.

Create a world with a camera

Download and save this world. as 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>

The important parts are here.

<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>

The <save> tag has an attribute enabled that must be set to true for images to be saved. The child tag <path> is a directory in which the camera images will be saved. If the directory does not exist, gazebo will try to create it. <width> and <height> set the resolution of the images. update_rate is the number of images per second that will be saved. This camera will output images with 1920x1080 resolution at 30 frames per second.

Run the world

Navigate to the folder where the world was downloaded and start gazebo.

gazebo --verbose camera_tutorial.world

Close gazebo after a few seconds.

The world above will save images to /tmp/camera_save_tutorial.

Examine the images

Inside /tmp/camera_save_tutorials there should be many images numbered sequentialy. They have the same resolution as the camera they were captured from (1920x1080). The first image is called default_camera_link_my_camera(1)-0000.jpg.

Convert Images to Video

Now that the camera images are saved to disk, they can be converted to a video with ffmpeg. This comand creates a video called my_camera.mp4 at 30 frames per second.

ffmpeg -r 30 -pattern_type glob -i '/tmp/camera_save_tutorial/default_camera_link_my_camera*.jpg' -c:v libx264 my_camera.mp4

If you have Ubuntu Trusty or a newer version, you might have avconv instead of ffmpeg (here is some of the backstory). The following command can be used with avconv:

avconv -framerate 30 -i /tmp/camera_save_tutorial/default_camera_link_my_camera\(1\)-%04d.jpg -c:v libx264 my_camera.mp4

Download the video here.