Michal, <div>I'd also suggest that you try running roswtf when things are running with problems.  That has a tf plugin to try to help detect common problems.  </div><div><br></div><div>Tully<br><br><div class="gmail_quote">

On Fri, Jul 2, 2010 at 9:29 AM, Brian Gerkey <span dir="ltr"><<a href="mailto:gerkey@willowgarage.com">gerkey@willowgarage.com</a>></span> wrote:<br><blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex;">

hi Michal,<br>
<br>
The fact that it's only rarely received incorrectly is peculiar.<br>
Sounds like part of the system is occasionally, or slowly, publishing<br>
a conflicting transform.  I would log all the tf data during a run:<br>
  rosbag record tf<br>
Then search through the resulting bag for the problem.  Something like<br>
this will pull out all the messages that declare a transform with<br>
base_footprint as the child:<br>
  rosbag filter in.bag out.bag 'topic == "tf" and<br>
m.transforms[0].header.frame_id == "base_footprint"'<br>
(where in.bag should be replaced by the name of bag created by the<br>
record step).  You can examine the filtered data with rostopic:<br>
  rostopic echo -b out.bag tf<br>
Presumably, in that data stream, you'll see occasional conflicting<br>
declarations of the parent of base_footprint.<br>
<font color="#888888"><br>
        brian.<br>
</font><div><div></div><div class="h5"><br>
On Fri, Jul 2, 2010 at 3:42 AM,  <<a href="mailto:Michal.Stolba@cis.strath.ac.uk">Michal.Stolba@cis.strath.ac.uk</a>> wrote:<br>
> Hi,<br>
><br>
> thanks for the reply. Gmapping is configured with <param name="odom_frame"<br>
> value="odom_combined"/><br>
><br>
> i'm launching this configuration:<br>
><br>
> <launch><br>
>  <include file="$(find pr2_machine)/$(env ROBOT).machine" /><br>
>  <include file="$(find hi_level_navigation)/launch/slam_gmapping.xml" /><br>
>  <include file="$(find pr2_navigation_teleop)/teleop.xml" /><br>
>  <include file="$(find pr2_navigation_perception)/lasers_and_filters.xml" /><br>
>  <include file="$(find pr2_navigation_perception)/ground_plane.xml" /><br>
>  <include file="$(find pr2_navigation_slam)/move_base.xml" /><br>
> </launch><br>
><br>
> where slam_gmapping.xml is:<br>
><br>
> <launch><br>
>    <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping"<br>
> output="screen"><br>
>      <remap from="scan" to="base_scan"/><br>
>      <param name="odom_frame" value="odom_combined"/><br>
>      <param name="map_update_interval" value="5.0"/><br>
>      <param name="maxUrange" value="16.0"/><br>
>      <param name="sigma" value="0.05"/><br>
>      <param name="kernelSize" value="1"/><br>
>      <param name="lstep" value="0.05"/><br>
>      <param name="astep" value="0.05"/><br>
>      <param name="iterations" value="5"/><br>
>      <param name="lsigma" value="0.075"/><br>
>      <param name="ogain" value="3.0"/><br>
>      <param name="lskip" value="0"/><br>
>      <param name="srr" value="0.01"/><br>
>      <param name="srt" value="0.02"/><br>
>      <param name="str" value="0.01"/><br>
>      <param name="stt" value="0.02"/><br>
>      <param name="linearUpdate" value="1.0"/><br>
>      <param name="angularUpdate" value="0.436"/><br>
>      <param name="temporalUpdate" value="5.0"/><br>
>      <param name="resampleThreshold" value="0.5"/><br>
>      <param name="particles" value="80"/><br>
>      <param name="xmin" value="-50.0"/><br>
>      <param name="ymin" value="-50.0"/><br>
>      <param name="xmax" value="50.0"/><br>
>      <param name="ymax" value="50.0"/><br>
>      <param name="delta" value="0.05"/><br>
>      <param name="llsamplerange" value="0.01"/><br>
>      <param name="llsamplestep" value="0.01"/><br>
>      <param name="lasamplerange" value="0.005"/><br>
>      <param name="lasamplestep" value="0.005"/><br>
>    </node><br>
> </launch><br>
><br>
> sometimes (quite rarely) the transform is received correctly.<br>
><br>
> Thanks very much,<br>
><br>
> Michal<br>
><br>
>> Perhaps gmapping is configured with odom_frame == base_footprint?<br>
>><br>
>>       brian.<br>
>><br>
>> On Fri, Jun 25, 2010 at 10:32 AM, Wim Meeussen<br>
>> <<a href="mailto:meeussen@willowgarage.com">meeussen@willowgarage.com</a>> wrote:<br>
>>> Michal,<br>
>>><br>
>>>> RESULTS: for /map to /base_footprint<br>
>>>> Chain is: /map -> /base_footprint -> /odom_combined<br>
>>>> Net delay     avg = 0.020768: max = 0.064<br>
>>><br>
>>> [...]<br>
>>><br>
>>>> the only weird thing is, that in rviz the transform arrows shows like<br>
>>>> this: /base_footprint -> /odom_combined -> /map<br>
>>>> might this be a sign of some problem?<br>
>>><br>
>>> Yes, This is most likely your problem. It appears that you have a tf<br>
>>> publisher from map to base_footprint, and another publisher from<br>
>>> odom_combined to base_footprint. So the base_footprint frame has two<br>
>>> parents.  In our setup we have amcl publish the transform from map to<br>
>>> odom combined, and the robot pose ekf publish the transform from<br>
>>> odom_combined to base_footprint.  What setup are you running? Did you<br>
>>> reconfigure amcl to publish a different tf transform?<br>
>>><br>
>>> Wim<br>
>>><br>
>>><br>
>>><br>
>>><br>
>>><br>
>>> --<br>
>>> Wim Meeussen<br>
>>> Willow Garage Inc.<br>
>>> <<a href="http://www.willowgarage.com" target="_blank">http://www.willowgarage.com</a>)<br>
>>> _______________________________________________<br>
>>> ros-users mailing list<br>
>>> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
>>> <a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
>>><br>
>> _______________________________________________<br>
>> ros-users mailing list<br>
>> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
>> <a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
>><br>
><br>
><br>
> _______________________________________________<br>
> ros-users mailing list<br>
> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
> <a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
><br>
_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
</div></div></blockquote></div><br><br clear="all"><br>-- <br>Tully Foote<br>Systems Engineer<br>Willow Garage, Inc.<br><a href="mailto:tfoote@willowgarage.com">tfoote@willowgarage.com</a><br>(650) 475-2827<br>
</div>