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

Gazebo own Materials Path

asked 2012-05-07 00:43:44 -0500

pmarinplaza gravatar image

updated 2012-07-02 14:06:04 -0500

Eric Perko gravatar image

Hi there!!

I am beginning working with gazebo and Ros-Fuerte. I created a package with this comand:

roscreate-pkg gazebo_tutorials std_msgs rospy roscpp gazebo

In the Directory I insert this other directories:

  • models
  • worlds
  • Media

by my own.

In media I have other dir which it calls script and textures where I save my textures and my materials.

In scripts's dir I have pablo.material with the materials who I use.

The problem is:

¿How I tell the ROS launch the path where I have my materials?

My Launch file is the next:

<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="pablo_server" pkg="gazebo" type="gazebo" args="$(find gazebo_tutorials)/worlds/pablo.world" respawn="false" output="screen">
    <env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_tutorials)/Media/scripts:$(find pr2_ogre):$(find gazebo)/gazebo/share/gazebo" />
  </node>

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

  </group>

</launch>

The error is the next:

$ roslaunch AlmacenEstanteCorto.launch 
... logging to /home/pablo/.ros/log/dc982eb6-9834-11e1-b77f-5404a64baafd/roslaunch-pablo-8415.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://pablo:45181/

SUMMARY
========

PARAMETERS
 * /rosdistro
 * /rosversion
 * /use_sim_time

NODES
  /
    empty_world_server (gazebo/gazebo)
    gazebo_gui (gazebo/gazebo)

auto-starting new master
process[master]: started with pid [8431]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to dc982eb6-9834-11e1-b77f-5404a64baafd
process[rosout-1]: started with pid [8444]
started core service [/rosout]
process[empty_world_server-2]: started with pid [8458]
process[gazebo_gui-3]: started with pid [8466]
Gazebo multi-robot simulator, version 1.0.0
Copyright (C) 2011 Nate Koenig, John Hsu, Andrew Howard, and contributors.
Released under the Apache 2 License.
http://gazebosim.org

Gazebo multi-robot simulator, version 1.0.0
Copyright (C) 2011 Nate Koenig, John Hsu, Andrew Howard, and contributors.
Released under the Apache 2 License.
http://gazebosim.org

[ INFO] [1336388861.484489333]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
Msg Waiting for master
Msg Connected to gazebo master @ http://localhost:11345
Exception [Master.cc:66] Unable to start server[Address already in use]

[gazebo_gui-3] process has died [pid 8466, exit code 134, cmd /opt/ros/fuerte/stacks/simulator_gazebo/gazebo/scripts/gazebo __name:=gazebo_gui __log:=/home/pablo/.ros/log/dc982eb6-9834-11e1-b77f-5404a64baafd/gazebo_gui-3.log].
log file: /home/pablo/.ros/log/dc982eb6-9834-11e1-b77f-5404a64baafd/gazebo_gui-3*.log

terminate called after throwing an instance of 'gazebo::common::Exception'
Aborted
[gazebo_gui-3] process has died [pid 8466, exit code 134, cmd /opt/ros/fuerte/stacks/simulator_gazebo/gazebo/scripts/gazebo __name:=gazebo_gui __log:=/home/pablo/.ros/log/dc982eb6-9834-11e1-b77f-5404a64baafd/gazebo_gui-3.log].
log file: /home/pablo/.ros/log/dc982eb6-9834-11e1-b77f-5404a64baafd/gazebo_gui-3*.log
[ INFO] [1336388863.148312684, 0.023000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1336388863.186636730, 0.061000000]: Starting to spin physics dynamic reconfigure node...

Any Idea?? this problem is the same when I want to use models by my own written in .model (URDF)

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
4

answered 2012-05-07 02:17:05 -0500

rtoris288 gravatar image

I noticed you correctly added 'gazebo' as a dependency which adds <depend package="gazebo"/> in the packages manifest. In addition to this, you need to add your package to Gazebo's media path inside of the package's manifest. Add the following to your manifest.xml:

<export>
    <gazebo gazebo_media_path="${prefix}" />
</export>

After this, rebuild the package and Gazebo should find your folders. This way, you won't need <env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_tutorials)/Media/scripts:$(find pr2_ogre):$(find gazebo)/gazebo/share/gazebo" /> inside your launch file as well.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-05-07 00:43:44 -0500

Seen: 3,248 times

Last updated: May 07 '12