ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
7

gazebo_ros_camera not loading in Fuerte

asked 2012-05-04 04:36:19 -0500

rtoris288 gravatar image

I recently upgraded to ROS Fuerte on Ubuntu 12.04 and am unable to load my old Gazebo camera files. I have an empty world spawned and running and then attempt to spawn my camera model in a launch file:

<launch>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>

<!-- set use_sim_time flag -->
<group if="$(arg use_sim_time)">
    <param name="/use_sim_time" value="true" />
</group>

<!-- start empty world -->
<node name="empty_world_server" pkg="gazebo" type="gazebo" args="$(find gazebo_worlds)/worlds/empty_throttled.world" respawn="false" output="screen" />

<!-- start gui -->
<group if="$(arg gui)">
    <node name="gazebo_gui" pkg="gazebo" type="gui" respawn="false" output="screen"/>
</group>

<node name="spawn_east_camera" pkg="gazebo" type="spawn_model" args="-file $(find rrl_simulation)/robots/test.urdf -urdf -x -2.5 -z 2.0 -P 0.87 -model east_camera" respawn="false" output="screen" />

</launch>

The following is the URDF of the camera:

<?xml version="1.0"?>

<robot name="east_camera" xmlns:body="&lt;a href=" http:="" playerstage.sourceforge.net="" gazebo="" xmlschema="" #body"="">http://playerstage.sourceforge.net/gazebo/xmlschema/#body" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://ros.org/wiki/xacro" > <link name="east_camera_link"> <inertial> <mass value="1"/> <origin xyz="0 0 0"/> <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/> </inertial> </link>

<gazebo reference="east_camera">
    <sensor:camera name="east_camera_sensor">
        <imageSize>640 480</imageSize>
        <imageFormat>R8G8B8</imageFormat>
        <hfov>90</hfov>
        <nearClip>0.01</nearClip>
        <farClip>100</farClip>
        <updateRate>30.0</updateRate>
        <controller:gazebo_ros_camera name="east_camera_controller" plugin="libgazebo_ros_camera.so">
            <alwaysOn>true</alwaysOn>
            <updateRate>10.0</updateRate>
            <imageTopicName>sim_east_camera/image_raw</imageTopicName>
            <interface:camera name="east_camera_interface" />
        </controller:gazebo_ros_camera>
    </sensor:camera>
    <turnGravityOff>true</turnGravityOff>
    <material>Gazebo/Blue</material>
</gazebo>

</robot>

Once I try and spawn in, the following errors are produced:

... logging to /home/rctoris/.ros/log/d7e20176-95f5-11e1-9b89-782bcbad8931/roslaunch-MAGLEV-26292.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://MAGLEV:51648/

SUMMARY
========

PARAMETERS
 * /rosdistro
 * /rosversion
 * /use_sim_time

NODES
  /
    empty_world_server (gazebo/gazebo)
    gazebo_gui (gazebo/gui)
    spawn_east_camera (gazebo/spawn_model)

auto-starting new master
Exception AttributeError: AttributeError("'_DummyThread' object has no attribute '_Thread__block'",) in <module 'threading' from '/usr/lib/python2.7/threading.pyc'> ignored
process[master]: started with pid [26308]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to d7e20176-95f5-11e1-9b89-782bcbad8931
Exception AttributeError: AttributeError("'_DummyThread' object has no attribute '_Thread__block'",) in <module 'threading' from '/usr/lib/python2.7/threading.pyc'> ignored
process[rosout-1]: started with pid [26321]
started core service [/rosout]
Exception AttributeError: AttributeError("'_DummyThread' object has no attribute '_Thread__block'",) in <module 'threading' from '/usr/lib/python2.7/threading.pyc'> ignored
process[empty_world_server-2]: started with pid [26335]
Exception AttributeError: AttributeError("'_DummyThread' object has no attribute '_Thread__block'",) in <module 'threading' from '/usr/lib/python2.7/threading.pyc'> ignored
process[gazebo_gui-3]: started with pid [26343]
Gazebo multi-robot simulator, version 1.0.1
Copyright (C) 2011 Nate Koenig, John Hsu, Andrew Howard, and contributors.
Released under ...
(more)
edit retag flag offensive close merge delete

Comments

I also have the same error ("Exception AttributeError: AttributeError") on several of my packages. Hope this thread will solve our problem

MorganCormier gravatar image MorganCormier  ( 2012-05-05 04:49:57 -0500 )edit

4 Answers

Sort by ยป oldest newest most voted
3

answered 2012-05-09 08:14:10 -0500

rtoris288 gravatar image

updated 2012-09-17 03:09:01 -0500

After looking around for a little while I was able to recreate a gazebo_ros_camera. Here is the new .model file as an example for anyone looking to create a camera to stream ROS images in the future:

<gazebo version='1.0'>
  <model name="overhead_camera">
    <link name="link">
      <origin pose="0 0 0 0 0 0"/>

      <inertial mass="0.1">
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
      </inertial>

      <visual name="visual">
        <origin pose="0 0 0 0 0 0"/>
        <geometry>
          <box size="0.1 0.1 0.1"/>
        </geometry>
      </visual>

      <sensor name='camera' type='camera' always_on='1' update_rate='30' visualize='true'>
        <camera>
          <horizontal_fov angle='1.57079633'/>
          <image width='640' height='480' format='R8G8B8'/>
          <clip near='0.1' far='100'/>
        </camera>
        <plugin name="camera_plugin" filename="libgazebo_ros_camera.so">
            <alwaysOn>true</alwaysOn>
            <imageTopicName>image_raw</imageTopicName>
            <cameraInfoTopicName>camera_info</cameraInfoTopicName>
            <updateRate>30.0</updateRate>
            <cameraName>overhead_camera</cameraName>
            <frameName>overhead_camera_frame</frameName>
            <CxPrime>320.5</CxPrime>
            <Cx>320.5</Cx>
            <Cy>240.5</Cy>
            <hackBaseline>0</hackBaseline>
            <focalLength>320.000101</focalLength>
            <distortionK1>0.0</distortionK1>
            <distortionK2>0.0</distortionK2>
            <distortionK3>0.0</distortionK3>
            <distortionT1>0.0</distortionT1>
            <distortionT2>0.0</distortionT2>
        </plugin>
      </sensor>
    </link>
  </model>
</gazebo>
edit flag offensive delete link more
0

answered 2012-05-09 05:06:23 -0500

thebyohazard gravatar image

I think this is (at least in part) a python bug in threading.py of python 2.7. I got the same error messages of

Exception AttributeError: AttributeError("'_DummyThread' object has no attribute '_Thread__block'",) in < module 'threading' from '/usr/lib/python2.7/threading.pyc'> ignored

when I tried to launch the openni_driver or run the openni_camera/test/test_launch.py test.

There's a patch and discussion for it here.

It might not be all that's wrong (it didn't fix all my errors, anyway), but it should make those pertaining to the dummy threads go away.

edit flag offensive delete link more

Comments

1

roscore ticket #3950 says this is a Python bug, but does no harm. The plan is to wait for Ubuntu to distribute the fix: https://code.ros.org/trac/ros/ticket/3950

joq gravatar image joq  ( 2012-05-09 05:14:35 -0500 )edit
1

Thanks for the answer. I was hoping to find a solution to the "Error [CameraPlugin.cc:39] CameraPlugin requires a CameraSensor." problem which I figured out and will post below. I also was wondering about the AttributeError mentioned about so thank you again!

rtoris288 gravatar image rtoris288  ( 2012-05-09 08:11:44 -0500 )edit
0

answered 2012-10-18 23:30:07 -0500

Neostek gravatar image

updated 2012-10-18 23:56:44 -0500

Hello,

I tried to use your code without any success. My problem is that it seems that it is not able to run the plugin (neither in the constructor where I placed a cout).

I have to enter in details: if I create a .model file and the I spawn it with rosrun it works. If I adjust it as in the following link it does not.

You can find my files here:

http://answers.ros.org/question/46216/ros-fuerte-plugin/

If you could please give me a feedback, it would be great.

Thanks in advance,

Neostek

edit flag offensive delete link more
0

answered 2012-11-29 20:30:43 -0500

Jordi Pages gravatar image

Hi, we have encountered the same problem when migrating our REEM humanoid model (https://github.com/pal-robotics) from Electric to Fuerte.

When launching Gazebo the same error appears:

Error [CameraPlugin.cc:39] CameraPlugin requires a CameraSensor.

As a work-around, we did fixed the issue using the libgazebo_ros_prosilica.so plugin rather than the libgazebo_ros_camera.so. Then, in the gazebo.xacro file setting up the camera we use the following controller:

< controller:gazebo_ros_prosilica name="${name}_controller" plugin="libgazebo_ros_prosilica.so" >

Using this plugin may require some additional tags to be set and some others have different names (focalLength, distortionK1, ...).

edit flag offensive delete link more

Question Tools

6 followers

Stats

Asked: 2012-05-04 04:36:19 -0500

Seen: 2,595 times

Last updated: Nov 29 '12