Spawner gets blocked when trying to use libhector_gazebo_ros_sonar

asked 2017-05-22 07:47:08 -0500

SorinV gravatar image

updated 2017-05-22 09:51:30 -0500

Hi guys! To get to the point, I have an .xacro file where I am creating a simple 3-wheeled robot. I am trying to include a camera sensor that works fine and 3 sonar sensors using libhector_gazebo_ros_sonar. When I include the sonars the launching process stops at:

  [INFO] [1495446798.750176, 0.000000]: Calling service /gazebo/spawn_urdf_model
  [ INFO] [1495446798.857894558, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.

If I don't kill the process it fills up my RAM and everything freezes

After I kill the process with CTRL+C i see this warning:

[WARN] [1495446813.634902, 0.032000]: Controller Spawner couldn't find the expected controller_manager ROS interface.

Code for sonar:

<xacro:macro name="sonar_sensor" params="sid dx dy dz rot jr jh plink ray_count field_of_view min_range max_range">
 <link name="sonar${sid}">
    <visual>
      <origin rpy="0 0 ${rot}" xyz="0 0 0"/>
      <geometry>
        <box size="${dx} ${dy} ${dz}"/>
      </geometry>
       <material name="red"/>
    </visual>
 </link>

 <joint name="sonar${sid}_joint" type="fixed">
    <parent link="${plink}"/>
    <child link="sonar${sid}"/>
    <origin rpy="0 0 0" xyz="${cos(rot)*jr} ${sin(rot)*jr} ${jh}"/>
  </joint>

  <gazebo reference="sonar${sid}">
   <material>Gazebo/Red</material>
    <sensor name="sonar_sensor${sid}" type="ray">
      <always_on> true</always_on>
      <update_rate>30.0</update_rate>
      <ray>
        <scan>
          <horizontal>
            <samples>${ray_count}</samples>
            <resolution>1</resolution>
            <min_angle>-${field_of_view/2}</min_angle>
            <max_angle> ${field_of_view/2}</max_angle>
          </horizontal>
          <vertical>
            <samples>${ray_count}</samples>
            <resolution>1</resolution>
            <min_angle>-${field_of_view/2}</min_angle>
            <max_angle> ${field_of_view/2}</max_angle>
          </vertical>
        </scan>
        <range>
          <min>${min_range}</min>
          <max>${max_range}</max>
          <resolution>0.01</resolution>
          </range>
      </ray>

      <plugin name="sonar${sid}_controller" filename="libhector_gazebo_ros_sonar.so">
        <gaussianNoise>0.005</gaussianNoise>
        <topicName>sonar</topicName>
        <frameId>sonar_link</frameId>
      </plugin>
    </sensor>
  </gazebo>

</xacro:macro>

I include the sonar like this:

<xacro:sonar_sensor sid="1" dx="${l_sen}" dy="${L_sen}" dz="${L_sen}" rot="0" jr="${r_base-0.005}" jh="-0.2" plink="base_link" ray_count="640" field_of_view="${pi}" min_range="0.01" max_range="5"/>

No parsing error when parsing directly the .xacro file to .urdf or .sdf. There may be a problem with the way I try to use the library or the namespaces, but I am not configuring those, just / like so:

 <gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
      <robotNamespace>/</robotNamespace>
    </plugin>
  </gazebo>

I include the spawner in the .launch file like so:

<node name="robot_controller_spawner" pkg="controller_manager" type="spawner" args="[joint controllers here]"/>

system: Ubuntu 16.04, ROS kinetic, Gazebo 7 llibraries: libhector_gazebo_ros_sonar and ros-kinetic-gazebo-ros-control installed with sudo apt-get No path problem for ROS. The Gazebo path returns nothing but I set that up and still does not work. Again, everything spawns without the sonars.

Not sure if this is the same problem.

Thank you in advance for any suggestions. I asked also on ROS forum here.

UPDATE 1 Managed to narrow it down to the ray tag. It spawns when I comment out the vertical caracteristics but still have the warning:

[WARN] [1495446813.634902, 0.032000]: Controller Spawner couldn't find the expected controller_manager ROS interface.

and the odometry data is unavailable.

UPDATE 2 Actually completely removing the vertical tag ... (more)

edit retag flag offensive close merge delete