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

Gazebo IRSensor parameters configuration xml

asked 2011-09-21 21:21:24 -0500

jrcapriles gravatar image

updated 2011-09-22 20:17:46 -0500

Hi everyone,

I was working with simulator_gazebo developer version to create IR and SonarSensor for gazebo (in diamondback), and i made it!! but now, in order to use my work everyone need to install my modified gazebo instead of using the ros gazebo (this because i needed to modify some gazebo files in order to make it work). Because of that I'll try to implement my sensors without modifying the original gazebo simulator code (a proper plugin). But i have now some problems, my function for IR readings do (i create my own package and i mimic the hokuyo node implementation):

   ... 
   void GazeboRosIR::PutIRData()
    {
      int irCount = this->myParent->GetIRCount();
      std::cout<<"[DEBUG] IRCount "  << this->myParent->GetIRCount()  <<std::endl;
      double Range;

      for (int i=0; i<irCount; i++)
      {
          Range=this->myParent->GetRange(i);

      }
    ...
    }

The getIRCount() always return 0, and then my code doesn't read. (This GetIRCount() is a function from IRSensor.hh (gazebo/gazebo/include/gazebo) it should return the number of ir specified in the configuration xml file, looking the source code the reading from xml inside https://kforge.ros.org/gazebo/trac/browser/server/sensors/ir/IRSensor.cc">IRSensor do:

return this->irBeams.size();

This mean that irBeams isn't fulfilled anywhere and then it's always 0. Looking at the source code I didn't find where the irBeams is created and fulfilled.

In my loading parameters xml (for pr2) i do:

  <xacro:macro name="ir_gazebo_v0" params="name ros_topic update_rate">
    <gazebo reference="${name}_link">
      <sensor:ir name="${name}">
        <irCount>5</irCount>
        <rangeCount>5</rangeCount>
        <minAngle>-0.17453</minAngle>
        <maxAngle>0.17453</maxAngle>
        <minRange>0.08</minRange>
        <maxRange>10.0</maxRange>
        <origin>0.0 0.0 0.0</origin>
        <displayRays>false</displayRays>
        <sensorName>irsensor</sensorName>
        <updateRate>${update_rate}</updateRate>
        <controller:gazebo_ros_ir name="gazebo_ros_${name}_controller" plugin="libgazebo_ros_ir.so">
              <gaussianNoise>0.005</gaussianNoise>
              <alwaysOn>true</alwaysOn>
              <updateRate>${update_rate}</updateRate>
              <topicName>${ros_topic}</topicName>
              <frameName>${name}_link</frameName>
              <interface:irarray name="gazebo_ros_${name}_iface" />
         </controller:gazebo_ros_ir>
      </sensor:ir>
    </gazebo>
  </xacro:macro>

Where gazebo load/save the configuration parameters? How is the good way to configure the IRSensor parameters in order to use my implementation?

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2011-09-22 05:45:27 -0500

updated 2011-09-22 08:25:40 -0500

Looking at the IRSensor source code, I think you need to have one <ir> XML child node per actual IR sensor on the IR ring. The only example of a config file that I could find is here, but that seems to be really outdated.

Edit: If you look at the source code, you can see that the parameter irCount is not read. Instead, I guess it should return the number of <ir> children, although I cannot see where this is done in the source code.

Edit 2: I think the XML should look something like this, but I haven't tested it yet:

<xacro:property name="ir_min_range" value="0.1" />
<xacro:property name="ir_max_range" value="0.8" />
<xacro:property name="ir_res_range" value="0.03" />
<xacro:property name="ir_fov" value="0.074859848" />

<gazebo reference="base_link">
  <sensor:ir name="ir_ring">
    <irCount>1</irCount>
    <ir name="ir_back">
      <rayCount>5</rayCount>
      <rangeCount>5</rangeCount>
      <minAngle>${M_PI - ir_fov/2}</minAngle>
      <maxAngle>${M_PI + ir_fov/2}</maxAngle>
      <minRange>${ir_min_range}</minRange>
      <maxRange>${ir_max_range}</maxRange>
      <resRange>${ir_res_range}</resRange>
      <origin>-0.217 0 0</origin>
      <displayRays>true</displayRays>
    </ir>
    <updateRate>100.0</updateRate>
  </sensor:ir>
</gazebo>
edit flag offensive delete link more

Comments

Hi Martin, thanks for your help! I tried this but it didn't work. I found some differences between some IRSensor.cc revisions, i updated the current question with the IRSensor in use, but the response is the same it always return 0, I think the problems is that irBeams isn't fulfilled anywhere
jrcapriles gravatar image jrcapriles  ( 2011-09-22 20:00:19 -0500 )edit
This seems like a bug in Gazebo. Ticket created: https://kforge.ros.org/gazebo/trac/ticket/30
Martin Günther gravatar image Martin Günther  ( 2011-09-22 21:59:44 -0500 )edit
Yes, i think is a bug, I have a solution to that problem (in my modified gazebo i changed the IRSensor.cc and IRSensor.hh) what can i do in order to help? contact gazebo administrator and send the modified package (a patch)? Or, what are the standard steps to contribute? Thanks for your help!
jrcapriles gravatar image jrcapriles  ( 2011-09-22 22:54:08 -0500 )edit
You can attach the patch to the bug report I created (see above). You'll have to register and login to do that.
Martin Günther gravatar image Martin Günther  ( 2011-09-22 23:26:10 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2011-09-21 21:21:24 -0500

Seen: 1,233 times

Last updated: Sep 22 '11