Gazebo | Ignition | Community
Ask Your Question
1

Forcing Gazebo to render at fixed intervals or how to record a video of a simulation

asked 2014-09-26 16:51:17 -0600

NickDP gravatar image

updated 2014-09-26 17:01:23 -0600

I want to be able to get a video of a Gazebo simulation. As far as I can tell, people are doing that by recording their desktop with things like RecordMyDesktop. I don't find this to be very elegant, but more importantly my simulation runs very slow and I want the video to be real-time speed. The reason why the simulation is slow is that I have an external program communicating with a Gazebo plugin. The plugin's OnUpdate() blocks until communication with the external program completes.

To get around this, I wanted to save images from the simulation at every simulation step with the help of a system plugin as described in this tutorial and then convert them into a video with ffmpeg/avconv. However, I found that the video produced is very choppy. It looks like the plugin's call back function event::Events::ConnectPreRender(boost::bind(&ImagePlugin::Update, this))); is not actually called at fixed simulation time intervals. This appears to be true even when limiting the simulation by adding the following to the .world file, which effectively forces the real time factor to be 0.01:

<physics type="ode">
      <real_time_update_rate>10.00000</real_time_update_rate>
      <max_step_size>0.001000</max_step_size>
</physics>

This also not very satisfactory because with this, the simulation is running at a very conservative speed.

The next thing I tried was to run the simulation and record/log it, then filter the log to get a recording at a given update rate (with the -z argument) and playing that back with the system plugin that records the images:

# run the simulation headlessly and record it    
gzserver -r my_scara.world
# filter the log file at 30Hz
gz log -e -f ~/.gazebo/log/*/gzserver/state.log -z 30 --filter *.pose/*.pose > /tmp/filtered_state.log
# run the simulation from the recording and take pictures
gazebo -u -p /tmp/filtered_state.log -g image_plugin/build/libimage_plugin.so

This, however, runs the simulation very quickly and the plugins' Update() function is not executed 30 times per simulation-time second.

So my question is this: What can I do to get an image of the simulation at fixed intervals?

Thanks in advance.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2014-09-30 17:38:46 -0600

nkoenig gravatar image

updated 2015-01-09 14:40:26 -0600

You can insert a camera sensor that saves frames to disk. Attach this camera to a static model, such as a simple box, and you can then position the camera in space. Here is an example model that will store image frames in /tmp:

<?xml version="1.0" ?>
<sdf version="1.5">
  <model name="camera">
    <link name="link">
      <pose>0.05 0.05 0.05 0 0 0</pose>
      <inertial>
        <mass>0.1</mass>
      </inertial>
      <collision name="collision">
        <geometry>
          <box>
            <size>0.1 0.1 0.1</size>
          </box>
        </geometry>
      </collision>
      <visual name="visual">
        <geometry>
          <box>
            <size>0.1 0.1 0.1</size>
          </box>
        </geometry>
      </visual>
      <sensor name="camera" type="camera">
        <camera>
          <horizontal_fov>1.047</horizontal_fov>
          <image>
            <width>640</width>
            <height>480</height>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
          <save enabled="true">
            <path>/tmp</path>
          </save>
        </camera>
        <always_on>1</always_on>
        <update_rate>30</update_rate>
        <visualize>true</visualize>
      </sensor>
    </link>
  </model>
</sdf>
edit flag offensive delete link more

Comments

That's exactly what I need! Thanks a lot.

NickDP gravatar imageNickDP ( 2014-10-01 12:37:53 -0600 )edit
1

Is there a way to save a the most recent camera frame through either a console command or C++ program without having to enable <save>?

K. Zeng gravatar imageK. Zeng ( 2014-10-03 09:37:55 -0600 )edit

I believe you can just copy rendered image to OpenCV image and save whole stream to video file (if you ok with using extrenal library with your code). Other way will be use gazebo-ros-pkgs and dump video/image from topic. Finally, you could publish rendered image using Gazebo topic and save with your client code.

kpykc gravatar imagekpykc ( 2014-10-07 11:15:55 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2014-09-26 16:51:17 -0600

Seen: 4,426 times

Last updated: Jan 09 '15