[ros-users] AMCL bug?

Torsten Fiolka fiolka at cs.uni-bonn.de
Tue Nov 2 09:02:53 UTC 2010


Hi all,

same problem here, AMCL locks up very fast in Stage and sometimes on the
real robot.

My best parameters so far are:

 <node pkg="amcl" type="amcl" name="amcl">
  <remap from="scan" to="laserscan"/>
  <param name="min_particles" value="100"/>
  <param name="max_particles" value="500"/>
  <param name="initial_pose_x" value="-4.5"/>
  <param name="initial_pose_y" value="-0.5"/>
  <param name="laser_max_beams" value="30"/>
  <param name="laser_model_type" value="beam"/>
 </node>

With these parameters AMCL runs nearly normal; more than 700 particles
and the laser model "likelihood field" are causing problems.

AMCL still locks up if you move (or just touch) the robot with the mouse
in stage; with the parameters above the particlecloud disperses one or
two times while moving the robot, but then amcl is dead.
Interestingly, on the robot it is more stable, but still locks up sometimes.

It stops sending anything (transforms, topics) and CPU-load goes up to
100%. I have seen no messages from AMCL before locking up.

Tested on: ROS boxturtle/cturtle on Ubuntu 9.10 (2.6.31) and 10.04
(2.6.32). Robot: iRobot roomba 500 with a Sick 300 laserscanner and a
notebook on top.

I hope this will help a bit to track down the problem.

Regards,
Torsten Fiolka

Am 27.10.2010 14:50, schrieb Eric Perko:
> Dominik,
> 
> A few questions to help debugging get started:
> 
>    1. Can you post your AMCL launch file with parameter values that
>       produces the problem?
>    2. If you have narrowed things down to just one or two parameters,
>       can you post both working and failing versions that differ only in
>       the parameter that leads to a problem?
>    3. Can you reproduce the crash in Stage or does it only happen with
>       the real robot?
>    4. You mention AMCL stops showing up in tf_monitor. Does it also stop
>       outputting on it's output topics such as amcl_pose or
>       particlecloud? You can check those with 'rostopic echo <topic>'.
>    5. Do you get any error output in the console where you started AMCL?
>       Anything in the log file for AMCL?
> 
> I'm definitely interested to see what parameters you are using - I had
> some similar sounding problems a few months ago while playing with the
> resampling parameters but didn't really spend much time looking into it.
> 
> - Eric
> 
> On Wed, Oct 27, 2010 at 4:28 AM, Dominik Franěk
> <dominik.franek at gmail.com <mailto:dominik.franek at gmail.com>> wrote:
> 
>     Hi guys and girls,
> 
>     recently I'm having difficulties running my robot as it stops working
>     after a very short time. I have narrowed the problem to AMCL, which
>     stops working either (probably) at it's first resampling, or some
>     longer time later. I have had all the navigation with amcl and static
>     map on both costmaps running all right for a long time and this error
>     started appearing during some testing of various parameters (no
>     changes in packages) and then stayed untill now, though I have tried
>     reverting or otherwise changing all I could think of. So, now some
>     details.
> 
>     My ROS and all substantial components are the most recent version,
>     including the yesterdays update. Costmaps are both using the same
>     static map with no marking/clearing. TF tree is default
>     (map->odom->base_link->laser_scan) and running on about 13Hz, all fine
>     on view_frames.  In rviz everything looks ok. Pose cloud appears after
>     setting initial pose.
>     When I send a goal, robot starts moving towards it, both in the real
>     and rviz. And after traversing around half a meter it freezes in rviz
>     (along with pose cloud and laser measurments), in command starts
>     printing transform timeout with pose timestamp staying on the same
>     value and amcl disappears from tf_monitor. In rxgraph and node info
>     amcl still looks all right though. In the real, robot keeps going
>     until it hits a wall... So the thing is, AMCL stops updating the pose
>     estimate.
>     What works a bit is to give the first goal very close, then the robot
>     gets to it alive, and then usually manages to get to a second goal
>     that can be far away. And then it freezes after reaching the second
>     goal.
> 
>     I have been trying to repair it for a long time and run out of ideas..
>      Would be gratefull for any help.
> 
>     Dominik
>     _______________________________________________
>     ros-users mailing list
>     ros-users at code.ros.org <mailto:ros-users at code.ros.org>
>     https://code.ros.org/mailman/listinfo/ros-users
> 
> 
> 
> 
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users




More information about the ros-users mailing list