Robotics StackExchange | Archived questions

Error :XML Element[sensor], child of element[model] not defined in SDF. Ignoring.[model] child while adding sonar sensor plugin

Trying to add sonar sensor to my bot and using pal-robotic/reems_plugin . Till now, able to compile the code with few warnings.

Made following changes in order to use this plugin

<sensor name ="sonar" type="ray">
   <rayCount>5</rayCount>
    <rangeCount>5</rangeCount>
    <verticalRayCount>1</verticalRayCount>
    <verticalRangeCount>1</verticalRangeCount>

    <minAngle>-16</minAngle>
    <verticalMinAngle>-16</verticalMinAngle>
    <maxAngle>16</maxAngle>
    <verticalMaxAngle>16</verticalMaxAngle>

    <minRange>0</minRange>
    <maxRange>7</maxRange>
    <resRange>0.01</resRange>
  <plugin name="gazebo_ros_sonar_controller" filename ="libgazebo_ros_sonar.so">
  <alwaysOn>true<alwaysOn>
  <updateRate>10</updateRate>
  <topicName>sonar</topicName>
  <frameId>base</frameId>
  <radiation>infrared</radiation>
  <fov>32</fov>
  </plugin>
</sensor>

where my already existing sdf file is :

<?xml version="1.0" ?>
<sdf version="1.4">
<model name="create">
<link name="base">
  <inertial>
    <pose>0.001453 -0.000453 0.029787 0 0 0</pose>
    <inertia>
      <ixx>0.058640</ixx>
      <ixy>0.000124</ixy>
      <ixz>0.000615</ixz>
      <iyy>0.058786</iyy>
      <iyz>0.000014</iyz>
      <izz>1.532440</izz>
    </inertia>
    <mass>2.234000</mass>
  </inertial>
  <collision name="base_collision">
    <pose>0 0 0.047800 0 0 0</pose>
    <geometry>
      <cylinder>
        <radius>0.016495</radius>
        <length>0.061163</length>
      </cylinder>
    </geometry>
  </collision>
  <visual name="base_visual">
    <pose>0 0 0.047800 0 0 0</pose>
    <geometry>
      <mesh>
        <uri>model://create/meshes/create_body.dae</uri>
      </mesh>
    </geometry>
  </visual>

  <collision name="front_wheel_collision">
    <pose>0.130000 0 0.017000 0 1.570700 1.570700</pose>
    <geometry>
      <sphere>
        <radius>0.018000</radius>
      </sphere>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>0</mu>
          <mu2>0</mu2>
          <fdir1>0 0 0</fdir1>
          <slip1>0</slip1>
          <slip2>0</slip2>
        </ode>
      </friction>
    </surface>
  </collision>
  <visual name="front_wheel_visual">
    <pose>0.130000 0 0.017000 0 1.570700 1.570700</pose>
    <geometry>
      <sphere>
        <radius>0.009000</radius>
      </sphere>
    </geometry>
  </visual>

  <collision name="rear_wheel_collision">
    <pose>-0.13 0 0.017 0 1.5707 1.5707</pose>
    <geometry>
      <sphere>
        <radius>0.015000</radius>
      </sphere>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>0</mu>
          <mu2>0</mu2>
          <fdir1>0 0 0</fdir1>
          <slip1>0</slip1>
          <slip2>0</slip2>
        </ode>
      </friction>
    </surface>
  </collision>
  <visual name="rear_wheel_visual">
    <pose>-0.130000 0 0.017000 0 1.570700 1.570700</pose>
    <geometry>
      <sphere>
        <radius>0.007500</radius>
      </sphere>
    </geometry>
  </visual>


  <sensor name="left_cliff_sensor" type="ray">
    <pose>0.070000 0.140000 0.027000 0 1.570790 0</pose>
    <ray>
      <scan>
        <horizontal>
          <samples>1</samples>
          <resolution>1.000000</resolution>
          <min_angle>0</min_angle>
          <max_angle>0</max_angle>
        </horizontal>
      </scan>
      <range>
        <min>0.010000</min>
        <max>0.040000</max>
        <resolution>0.100000</resolution>
      </range>
    </ray>
  </sensor>

  <sensor name="leftfront_cliff_sensor" type="ray">
    <pose>0.150000 0.040000 0.027000 0 1.570790 0</pose>
    <ray>
      <scan>
        <horizontal>
          <samples>1</samples>
          <resolution>1.000000</resolution>
          <min_angle>0</min_angle>
          <max_angle>0</max_angle>
        </horizontal>
      </scan>
      <range>
        <min>0.010000</min>
        <max>0.040000</max>
        <resolution>0.100000</resolution>
      </range>
    </ray>
  </sensor>

  <sensor name="right_cliff_sensor" type="ray">
    <pose>0.070000 -0.140000 0.027000 0 1.570790 0</pose>
    <ray>
      <scan>
        <horizontal>
          <samples>1</samples>
          <resolution>1.000000</resolution>
          <min_angle>0</min_angle>
          <max_angle>0</max_angle>
        </horizontal>
      </scan>
      <range>
        <min>0.010000</min>
        <max>0.040000</max>
        <resolution>0.100000</resolution>
      </range>
    </ray>
  </sensor>

  <sensor name="rightfront_cliff_sensor" type="ray">
    <pose>0.150000 -0.040000 0.027000 0 1.570790 0</pose>
    <ray>
      <scan>
        <horizontal>
          <samples>1</samples>
          <resolution>1.000000</resolution>
          <min_angle>0</min_angle>
          <max_angle>0</max_angle>
        </horizontal>
      </scan>
      <range>
        <min>0.010000</min>
        <max>0.040000</max>
        <resolution>0.100000</resolution>
      </range>
    </ray>
  </sensor>

  <sensor name="wall_sensor" type="ray">
    <pose>0.090000 -0.120000 0.059000 0 0 -1.000000</pose>
    <ray>
      <scan>
        <horizontal>
          <samples>1</samples>
          <resolution>1.000000</resolution>
          <min_angle>0</min_angle>
          <max_angle>0</max_angle>
        </horizontal>
      </scan>
      <range>
        <min>0.016000</min>
        <max>0.040000</max>
        <resolution>0.100000</resolution>
      </range>
    </ray>
  </sensor>
</link>


<link name="left_wheel">
  <pose>0 0.130000 0.032000 0 0 0</pose>
  <inertial>
    <inertia>
      <ixx>0.001000</ixx>
      <ixy>0</ixy>
      <ixz>0</ixz>
      <iyy>0.001000</iyy>
      <iyz>0</iyz>
      <izz>0.001000</izz>
    </inertia>
    <mass>0.010000</mass>
  </inertial>
  <collision name="collision">
    <pose>0 0 0 0 1.570700 1.570700</pose>
    <geometry>
      <cylinder>
        <radius>0.033000</radius>
        <length>0.023000</length>
      </cylinder>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>10</mu>
          <mu2>10</mu2>
          <fdir1>0 0 0</fdir1>
          <slip1>0</slip1>
          <slip2>0</slip2>
        </ode>
      </friction>
    </surface>
  </collision>
  <visual name="visual">
    <pose>0 0 0 0 1.570700 1.570700</pose>
    <geometry>
      <cylinder>
        <radius>0.033000</radius>
        <length>0.023000</length>
      </cylinder>
    </geometry>
  </visual>
</link>

<link name="right_wheel">
  <pose>0 -0.130000 0.032000 0 0 0</pose>
  <inertial>
    <inertia>
      <ixx>0.001000</ixx>
      <ixy>0</ixy>
      <ixz>0</ixz>
      <iyy>0.001000</iyy>
      <iyz>0</iyz>
      <izz>0.001000</izz>
    </inertia>
    <mass>0.010000</mass>
  </inertial>
  <collision name="collision">
    <pose>0 0 0 0 1.570700 1.570700</pose>
    <geometry>
      <cylinder>
        <radius>0.033000</radius>
        <length>0.023000</length>
      </cylinder>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>10</mu>
          <mu2>10</mu2>
          <fdir1>0 0 0</fdir1>
          <slip1>0</slip1>
          <slip2>0</slip2>
        </ode>
      </friction>
    </surface>
  </collision>
  <visual name="visual">
    <pose>0 0 0 0 1.570700 1.570700</pose>
    <geometry>
      <cylinder>
        <radius>0.033000</radius>
        <length>0.023000</length>
      </cylinder>
    </geometry>
  </visual>
</link>

<joint name="left_wheel" type="revolute">
  <parent>base</parent>
  <child>left_wheel</child>
  <axis>
    <xyz>0 1 0</xyz>
  </axis>
</joint>

<joint name="right_wheel" type="revolute">
  <parent>base</parent>
  <child>right_wheel</child>
  <axis>
    <xyz>0 1 0</xyz>
  </axis>
</joint>

<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
  <alwaysOn>true</alwaysOn>
  <updateRate>10</updateRate>
  <leftJoint>left_wheel</leftJoint>
  <rightJoint>right_wheel</rightJoint>
  <wheelSeparation>0.5380</wheelSeparation>
  <wheelDiameter>0.2410</wheelDiameter>
  <torque>20</torque>
  <commandTopic>cmd_vel</commandTopic>
  <odometryTopic>odom</odometryTopic>
  <odometryFrame>odom</odometryFrame>
  <robotBaseFrame>base_footprint</robotBaseFrame>
  </plugin>

while lauching the simulator with modified sdf file getting errors

Error [parser.cc:697] XML Element[sensor],child of element[model] not defined in SDF. 
Ignoring.model]
Error [parser.cc:688] Error reading element <model>
Error [parser.cc:348] Unable to read element <sdf>
Error:   Could not find the 'robot' element in the xml file
     at line 81 in /build/buildd/urdfdom-0.2.10+dfsg/urdf_parser/src/model.cpp
Error [parser_urdf.cc:2608] Unable to call parseURDF on robot model
Error [parser.cc:299] parse as old deprecated model file failed.
Error [World.cc:1527] Unable to read sdf string[<sdf version="1.4"><model nnamame="swarmb....

same for each bot and finally getting status: [swarmbot0/create_model-5] process has finished cleanly

Does anyone know what am I doing wrong? I'm using gazebo 2.2 and ros-indigo.

Thanks in advance!

Asked by Aman_singh on 2015-05-31 08:17:11 UTC

Comments

Answers

Hi, I pushed the sonar plugin from the PAL domain to the official ROS Gazebo plugins. The test should give you a good enough hint for confiruging it on your robot: https://github.com/ros-simulation/gazebo_ros_pkgs/blob/jade-devel/gazebo_plugins/test/test_worlds/gazebo_ros_range.world

OR have a look at the URDF of PMB2 (from PAL Robotics): The corresponding URDF files to use the plugin with a macro: https://github.com/pal-robotics/pmb2_robot/blob/indigo-devel/pmb2_description/urdf/sensors/range.urdf.xacro https://github.com/pal-robotics/pmb2_robot/blob/indigo-devel/pmb2_description/urdf/sensors/range.gazebo.xacro

and the place where it gets deployed: https://github.com/pal-robotics/pmb2_robot/blob/indigo-devel/pmb2_description/urdf/base/base.urdf.xacro#L124

Hope this helps!

Asked by Bence Magyar on 2016-02-05 13:05:21 UTC

Comments