Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Capturing images from the environment #287

Open
YagoGG opened this issue Jan 4, 2021 · 4 comments
Open

Capturing images from the environment #287

YagoGG opened this issue Jan 4, 2021 · 4 comments

Comments

@YagoGG
Copy link

YagoGG commented Jan 4, 2021

Hi!

I was wondering if it is possible to programatically capture rendered images of the environment.

I have seen in #199 that there is a "camera sensor" that is yet to be exposed in the API, but I believe that is not exactly what I am looking for. I do not need it to be a sensor in one of the robots, but just a visualization like the one you get with Ignition's GUI.

Not sure if this is even out of gym-ignition's scope, but since this is also the repo for the scenario bindings I thought it could fit here.

Please let me know if you need further details, and congratulations on the great work!

@diegoferigo
Copy link
Member

diegoferigo commented Jan 5, 2021

Hi @YagoGG, thanks for passing by! I'm not an expert in the rendering stack of Ignition Gazebo, if I don't mistake the GUI's view is actually a camera that does not differ from any on-board camera. If you check the documentation on GzScene3D, you can see that the view is defined by a <camera_pose> entry.

This being said, I think what you mean is compatible with #199. I still haven't thought about the API to expose, but I'd like to have a method that queries the available cameras of the world. Maybe the view point could even be a special case deserving a different method, or being the default of a world.getCamera(cameraName) when the argument is not given.

A while ago I started working on #249 but then I had to pause the PR due to other priorities. I'm not happy of that implementation, I had to vendor and modify the Sensors system to make it compatible with programmatic steps (otherwise image acquisition would not be synchronous and deterministic) and performances were pretty bad. I understand that having cameras is an important feature and it could be worth even if performance are not the best initially, and then iterating after bottlenecks are found.

Note that all other rendering cameras (rgb, thermal, etc) share the same infrastructure of the implemented depth camera, adding them would be trivial once that PR is finalized.

@YagoGG
Copy link
Author

YagoGG commented Jan 7, 2021

Hey @diegoferigo! Thank you for your detailed response.

I have been taking a detailed look at the pointers you provided, and your reasoning sounds completely logical to me. Regarding the API design, this is what makes the most sense to me too:

Maybe the view point could even be a special case deserving a different method, or being the default of a world.getCamera(cameraName) when the argument is not given.

Unfortunately, and after checking out the code in #249, I am afraid that I am not familiar enough with Ignition to continue working on it myself. But I'll definitely keep an eye on the repo, as I am really excited about gym-ignition and I might be able to use it in the future.

Cheers!

@diegoferigo
Copy link
Member

Unfortunately, and after checking out the code in #249, I am afraid that I am not familiar enough with Ignition to continue working on it myself.

This is understandable. Despite I'm already familiar with most of the Ignition stack, I remember it took me a considerable effort to get #249 (kind of) working.

Ok! I cannot guarantee a prompt finalization of the PR, I'm going to leave this issue open so that you and others can track the progress of this feature.

@FirefoxMetzger
Copy link
Contributor

It is possible to get camera images in pure python (+ compiling the protobuf ignition messages to python), since Ignition is talking protobuf passed over zmq sockets. Although, this usage may not be intended by Ignition Gazebo, so it's probably a hack 🤷.

Here is a (hacky/dirty) example:

from ignition.msgs.image_pb2 import Image
from scenario import gazebo as scenario_gazebo
from scenario import core as scenario_core
from itertools import count
import gym_ignition_environments
import numpy as np
import zmq
import subprocess
import socket
import os
import pwd
import numpy as np
import matplotlib.pyplot as plt 

ctx = zmq.Context()
camera_socket = ctx.socket(zmq.SUB)

# scenario_gazebo.set_verbosity(scenario_gazebo.Verbosity_info)

gazebo = scenario_gazebo.GazeboSimulator(
    step_size=0.001,
    rtf=1.0,
    steps_per_run=1
)
assert gazebo.insert_world_from_sdf("./panda_world_expanded.sdf")
gazebo.initialize()

world = gazebo.get_world()
panda = gym_ignition_environments.models.panda.Panda(
    world=world, position=[0.2, 0, 1.025])

# gazebo.gui()
gazebo.run(paused=True)

# this is a bad hack and should be implemented
# by talking the ign-transport discovery protocol
ign_topic = "/camera"
result = subprocess.check_output(f"ign topic -i -t {ign_topic}", shell=True)
address = result.decode("utf-8").split("\n")[1].split(",")[0].replace("\t", "").replace(" ", "")
camera_socket.connect(address)

# this could also be streamlined by speaking the ign-transport discovery protcol
host_name = socket.gethostname()
user_name = pwd.getpwuid(os.getuid())[0]
camera_socket.subscribe(f"@/{host_name}:{user_name}@{ign_topic}")

# weird hack to encourage ign-transport to actually publish camera messages
# start an echo subscriber and print the messages into the void to make ign 
# realize that something is listening to the topic
# tracking issue: https://github.com/ignitionrobotics/ign-transport/issues/225
echo_subscriber = subprocess.Popen(
    ["ign", "topic", "-e", "-t", ign_topic], 
    stdout=open(os.devnull, 'w')
)

# execute a bunch of steps (proof of concept)
for _ in range(int(1000)):
    gazebo.run(paused=False)

# fetch all camera messages published during that time
for frame_idx in count():
    try:
        msg = camera_socket.recv_multipart(zmq.NOBLOCK)
        proto_msg = Image()
        proto_msg.ParseFromString(msg[2])
        im = np.frombuffer(proto_msg.data, dtype=np.uint8).reshape((proto_msg.height, proto_msg.width, 3))
        plt.imshow(im)
        plt.savefig(f"frames/frame{frame_idx:0>4d}.jpg")
    except zmq.ZMQError:
        break

echo_subscriber.terminate()
gazebo.close()
panda_world_expanded.sdf
<sdf version='1.7'>
  <world name='panda_world'>
    <physics name='1ms' type='ignored'>
      <max_step_size>0.001</max_step_size>
      <real_time_factor>1</real_time_factor>
      <real_time_update_rate>1000</real_time_update_rate>
    </physics>
    <plugin name='ignition::gazebo::systems::Physics' filename='ignition-gazebo-physics-system'/>
    <plugin name='ignition::gazebo::systems::UserCommands' filename='ignition-gazebo-user-commands-system'/>
    <plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system'/>
    <plugin name='ignition::gazebo::systems::Sensors' filename='ignition-gazebo-sensors-system'>
      <render_engine>ogre</render_engine>
    </plugin>
    <light name='sun' type='directional'>
      <cast_shadows>1</cast_shadows>
      <pose>0 0 10 0 -0 0</pose>
      <diffuse>0.8 0.8 0.8 1</diffuse>
      <specular>0.2 0.2 0.2 1</specular>
      <attenuation>
        <range>1000</range>
        <constant>0.9</constant>
        <linear>0.01</linear>
        <quadratic>0.001</quadratic>
      </attenuation>
      <direction>-0.5 0.1 -0.9</direction>
      <spot>
        <inner_angle>0</inner_angle>
        <outer_angle>0</outer_angle>
        <falloff>0</falloff>
      </spot>
    </light>
    <gravity>0 0 -9.8</gravity>
    <magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
    <atmosphere type='adiabatic'/>
    <scene>
      <ambient>0.4 0.4 0.4 1</ambient>
      <background>0.7 0.7 0.7 1</background>
      <shadows>1</shadows>
    </scene>
    <model name='ground_plane'>
      <static>1</static>
      <link name='link'>
        <collision name='collision'>
          <geometry>
            <plane>
              <normal>0 0 1</normal>
              <size>100 100</size>
            </plane>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='visual'>
          <geometry>
            <plane>
              <normal>0 0 1</normal>
              <size>100 100</size>
            </plane>
          </geometry>
          <material>
            <ambient>0.8 0.8 0.8 1</ambient>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.8 0.8 0.8 1</specular>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
      </link>
      <plugin name='__default__' filename='__default__'/>
      <pose>0 0 0 0 -0 0</pose>
    </model>
    <model name='table1'>
      <static>1</static>
      <link name='link'>
        <collision name='surface'>
          <pose>0 0 1 0 -0 0</pose>
          <geometry>
            <box>
              <size>1.5 0.8 0.03</size>
            </box>
          </geometry>
          <surface>
            <friction>
              <ode>
                <mu>0.6</mu>
                <mu2>0.6</mu2>
              </ode>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='visual1'>
          <pose>0 0 1 0 -0 0</pose>
          <geometry>
            <box>
              <size>1.5 0.8 0.03</size>
            </box>
          </geometry>
          <material>
            <diffuse>1 1 1 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Wood</name>
            </script>
            <pbr>
              <metal>
                <albedo_map>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/table/3/files/Table_Diffuse.jpg</albedo_map>
              </metal>
            </pbr>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <collision name='front_left_leg'>
          <pose>0.68 0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='front_left_leg'>
          <pose>0.68 0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <material>
            <diffuse>0.5 0.5 0.5 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <collision name='front_right_leg'>
          <pose>0.68 -0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='front_right_leg'>
          <pose>0.68 -0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <material>
            <diffuse>0.5 0.5 0.5 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <collision name='back_right_leg'>
          <pose>-0.68 -0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='back_right_leg'>
          <pose>-0.68 -0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <material>
            <diffuse>0.5 0.5 0.5 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <collision name='back_left_leg'>
          <pose>-0.68 0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='back_left_leg'>
          <pose>-0.68 0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <material>
            <diffuse>0.5 0.5 0.5 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
      </link>
      <pose>0 0 0 0 -0 1.5708</pose>
      <plugin name='__default__' filename='__default__'/>
    </model>
    <model name='table2'>
      <static>1</static>
      <link name='link'>
        <collision name='surface'>
          <pose>0 0 1 0 -0 0</pose>
          <geometry>
            <box>
              <size>1.5 0.8 0.03</size>
            </box>
          </geometry>
          <surface>
            <friction>
              <ode>
                <mu>0.6</mu>
                <mu2>0.6</mu2>
              </ode>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='visual1'>
          <pose>0 0 1 0 -0 0</pose>
          <geometry>
            <box>
              <size>1.5 0.8 0.03</size>
            </box>
          </geometry>
          <material>
            <diffuse>1 1 1 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Wood</name>
            </script>
            <pbr>
              <metal>
                <albedo_map>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/table/3/files/Table_Diffuse.jpg</albedo_map>
              </metal>
            </pbr>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <collision name='front_left_leg'>
          <pose>0.68 0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='front_left_leg'>
          <pose>0.68 0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <material>
            <diffuse>0.5 0.5 0.5 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <collision name='front_right_leg'>
          <pose>0.68 -0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='front_right_leg'>
          <pose>0.68 -0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <material>
            <diffuse>0.5 0.5 0.5 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <collision name='back_right_leg'>
          <pose>-0.68 -0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='back_right_leg'>
          <pose>-0.68 -0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <material>
            <diffuse>0.5 0.5 0.5 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <collision name='back_left_leg'>
          <pose>-0.68 0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='back_left_leg'>
          <pose>-0.68 0.38 0.5 0 -0 0</pose>
          <geometry>
            <cylinder>
              <radius>0.02</radius>
              <length>1</length>
            </cylinder>
          </geometry>
          <material>
            <diffuse>0.5 0.5 0.5 1</diffuse>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Grey</name>
            </script>
          </material>
          <plugin name='__default__' filename='__default__'/>
        </visual>
      </link>
      <pose>0.794 0 0 0 -0 1.5708</pose>
      <plugin name='__default__' filename='__default__'/>
    </model>
    <model name='Avengers_Thor_PLlrpYniaeB'>
      <link name='link_0'>
        <visual name='visual'>
          <geometry>
            <mesh>
              <uri>file:///home/sebastian/.ignition/fuel/fuel.ignitionrobotics.org/googleresearch/models/avengers_thor_pllrpyniaeb/1/meshes/model.obj</uri>
            </mesh>
          </geometry>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <collision name='collision_0'>
          <geometry>
            <mesh>
              <uri>file:///home/sebastian/.ignition/fuel/fuel.ignitionrobotics.org/googleresearch/models/avengers_thor_pllrpyniaeb/1/meshes/model.obj</uri>
            </mesh>
          </geometry>
        </collision>
      </link>
      <pose>1 0.5 1.025 0 -0 0</pose>
      <plugin name='__default__' filename='__default__'/>
    </model>
    <model name='camera'>
      <pose>4 -0 1 0 -0 3.14</pose>
      <link name='link'>
        <pose>0.05 0.05 0.05 0 -0 0</pose>
        <inertial>
          <mass>0.1</mass>
          <inertia>
            <ixx>0.000166667</ixx>
            <iyy>0.000166667</iyy>
            <izz>0.000166667</izz>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyz>0</iyz>
          </inertia>
        </inertial>
        <collision name='collision'>
          <geometry>
            <box>
              <size>0.1 0.1 0.1</size>
            </box>
          </geometry>
          <surface>
            <friction>
              <ode/>
            </friction>
            <contact/>
          </surface>
        </collision>
        <visual name='visual'>
          <geometry>
            <box>
              <size>0.1 0.1 0.1</size>
            </box>
          </geometry>
          <plugin name='__default__' filename='__default__'/>
        </visual>
        <sensor name='camera' type='camera'>
          <camera>
            <horizontal_fov>1.047</horizontal_fov>
            <image>
              <width>320</width>
              <height>240</height>
            </image>
            <clip>
              <near>0.1</near>
              <far>100</far>
            </clip>
          </camera>
          <always_on>1</always_on>
          <update_rate>30</update_rate>
          <visualize>1</visualize>
          <topic>camera</topic>
          <plugin name='__default__' filename='__default__'/>
        </sensor>
      </link>
      <plugin name='__default__' filename='__default__'/>
    </model>
  </world>
</sdf>

For this to work, you will need to install the necessary python packages (most noteworthy pyzmq) and you will have to create python bindings for the protobuf messages (so you can deserialize them in python). To do this I've cloned the ign-msgs repo which has all the messages in the proto folder. From there it is a one-liner protoc -I=<path/to/proto/folder> --python_out=<path/to/script/folder> *.proto (from memory, ymmv).

One caveat of this approach is that the camera publishes at a much slower rate than the simulator steps (the example runs 1000 steps, and produces ~30 frames) so ensuring that the current simulator step and sensor message are in sync would require additional effort. It may be enough for the use-case of "just want to create some images/video" though.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

3 participants