Gazebo IRSensor parameters configuration xml
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?