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

How to improve AMCL pose estimate?

asked 2016-04-14 00:11:20 -0600

Megacephalo gravatar image

updated 2016-04-21 07:12:58 -0600

Hi all,

While developing my own path planner, I found out that AMCL cannot yield acceptable pose estimate despite modifying all possible parameters. Here (with more detailed observation) I recorded a video to show how erroneous the estimation is. The platform used is a differential non-holonomic vehicle, the sensors are Hokuyo laser range finder with Asus Xtion camera at the front. And the AMCL configuration is as below assumed the argument tags' values are all correct (why can't it show the /node tag at the end?):

<node pkg="amcl" type="amcl" name="amcl">
<param name="use_map_topic"             value="$(arg use_map_topic)"/>
<!-- Publish scans from best pose at a max of 10 Hz -->
<param name="odom_model_type"           value="diff"/>
<param name="odom_alpha5"               value="0.1"/>
<param name="gui_publish_rate"          value="10.0"/>
<param name="laser_max_beams"             value="60"/>
<param name="laser_max_range"           value="12.0"/>
<param name="min_particles"             value="500"/>
<param name="max_particles"             value="2000"/>
<param name="kld_err"                   value="0.05"/>
<param name="kld_z"                     value="0.99"/>
<param name="odom_alpha1"               value="0.2"/>
<param name="odom_alpha2"               value="0.2"/>
<!-- translation std dev, m -->
<param name="odom_alpha3"               value="0.2"/>
<param name="odom_alpha4"               value="0.2"/>
<param name="laser_z_hit"               value="0.5"/>
<param name="laser_z_short"             value="0.05"/>
<param name="laser_z_max"               value="0.05"/>
<param name="laser_z_rand"              value="0.5"/>
<param name="laser_sigma_hit"           value="0.2"/>
<param name="laser_lambda_short"        value="0.1"/>
<param name="laser_model_type"          value="likelihood_field"/>
<!-- <param name="laser_model_type" value="beam"/> -->
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="update_min_d"              value="0.25"/>
<param name="update_min_a"              value="0.2"/>
<param name="odom_frame_id"             value="$(arg odom_frame_id)"/> 
<param name="base_frame_id"             value="$(arg base_frame_id)"/> 
<param name="global_frame_id"           value="$(arg global_frame_id)"/>
<param name="resample_interval"         value="1"/>
<!-- Increase tolerance because the computer can get quite busy -->
<param name="transform_tolerance"       value="1.0"/>
<param name="recovery_alpha_slow"       value="0.0"/>
<param name="recovery_alpha_fast"       value="0.0"/>
<param name="initial_pose_x"            value="$(arg initial_pose_x)"/>
<param name="initial_pose_y"            value="$(arg initial_pose_y)"/>
<param name="initial_pose_a"            value="$(arg initial_pose_a)"/>
<remap from="scan"                      to="$(arg scan_topic)"/>

</node>

I have tried other packages such as humanoid_localization which keeps complaining of receiving errorneous occupancy grid maps, or fused /amcl_pose with wheel odometry with robot_localization. I also looked into hector_pose_estimation but concluded that there are no matching topics that I can give to the package. Another option is to replace AMCL with MRPT_localization. MRPT localization node does publish odom and I will look into how to generate map of its format now. Despite this, the rest of my attempts end in failure.
Thus, how do you resolve this kind of localization problem? Or is there an easy or effective way to get around it? Is there any other alternative apart from using AMCL? Thank you !

edit retag flag offensive close merge delete

Comments

What are your sensors and the platform that you are working with? Please also post the config file used for AMCL.

al-dev gravatar image al-dev  ( 2016-04-14 17:04:23 -0600 )edit

Thank you @al-dev and sorry for replying this late. I have added more information about the platform that I am using and updated the config file for AMCL.

Megacephalo gravatar image Megacephalo  ( 2016-04-21 04:00:05 -0600 )edit

It doesn't correctly format the </node> closing tag because it's indented with 3 spaces, not 4.

Martin Günther gravatar image Martin Günther  ( 2016-04-21 04:14:43 -0600 )edit

1 Answer

Sort by » oldest newest most voted
3

answered 2016-04-21 04:19:54 -0600

updated 2016-05-02 04:45:57 -0600

Your video looks as if there is something wrong with your odometry data. It looks as if the odometry information tells AMCL that it's turning twice as fast than it actually is. That can be caused for example by having a wrong wheel size or wheel distance in the odometry calculation.

Did you try setting the fixed frame in RViz to /odom (or whatever your odometry frame is called)? If you do that and show the laser scans, the scans should still be roughly aligned while the robot is moving around. That needs to be working before moving on to AMCL.

Update (Mon May 2): (how to compute the odometry)

There is some code that I wrote for computing the odometry here: gazebo_ros_diffdrive_uos.cpp:196-207

It's a Gazebo plugin for a six-wheeled robot, but it works basically the same on a real robot or with a different number of wheels.

It computes the odometry pose from the wheel velocities, and it also has a parameter that accounts for slippage etc. when turning corners (where the wheels are "fighting" each other). That parameter is called turning_adaptation in the code, and some values that we used both in Gazebo and on different physical robots are 0.64, 0.69, 0.95 (just to give you some idea). We found those parameters by visualizing the laser scan in the odom frame and rotating the robot in place. If it looked as if the robot rotated too fast, we reduced turning_adaptation, if it was too slow, we increased it.

That parameter turning_adaptation is the same what I called angular_factor in the comments below. (Both are bad names). The Gazebo plugin doesn't have a linear_factorsince we never needed that. In the code, it would be a factor that's multiplied onto the variable dr.

edit flag offensive delete link more

Comments

I do set my frame on /map and I had arranged the wheels' size and spacing to appeal to the real robot. But the problem still remains. I think I'll try other odometry means by now. Thanks !

Megacephalo gravatar image Megacephalo  ( 2016-04-25 22:06:31 -0600 )edit

I think you misunderstood me. I was suggesting to use odom, not map, and verify that the odometry looks good. You should fix that first.

Martin Günther gravatar image Martin Günther  ( 2016-04-26 02:37:29 -0600 )edit

@Martin Günther, I am so sorry, I must have jumped the line somehow. And in this new video I did what you said, the odometry value is a little bit better, but the problem persists. What could I've gone wrong? Thanks you so so much !

Megacephalo gravatar image Megacephalo  ( 2016-04-26 05:18:29 -0600 )edit

Yes, it still looks as if the linear speed reported by odometry is about 2x the actual speed of the robot, and the angular speed reported by odometry is also higher. If you're sure nothing else is wrong with the odom calculation, I would suggest adding some params like ...

Martin Günther gravatar image Martin Günther  ( 2016-04-26 06:30:26 -0600 )edit

... "linear_factor = 0.5" and "angular_factor = 0.8" or so that you multiply in your odom calculation. These params may seem strange, but you probably need them to account for slippage etc. (which also happens in gazebo!). The actual values depend on the friction between wheels + ground etc.

Martin Günther gravatar image Martin Günther  ( 2016-04-26 06:31:59 -0600 )edit

I don't know how many wheels etc. your robot has, but on our six-wheeled diffdrive robot, we needed an angular factor of 0.7 to compensate for slippage in Gazebo (since the wheels are "fighting" each other when turning). For linear speed, we didn't need a compensating factor.

Martin Günther gravatar image Martin Günther  ( 2016-04-26 06:33:46 -0600 )edit

Then play around with these params until your odom results look reasonable; after that, go back to trying to configure AMCL.

Martin Günther gravatar image Martin Günther  ( 2016-04-26 06:34:31 -0600 )edit

Thanks for replying in such a detail! Since we developp our own robot from scratch, we write everything on our owwn andI am not sure by which mean can I calibrate my wheel odometry. Btw, where to find linear_factor and angular_factor?

Megacephalo gravatar image Megacephalo  ( 2016-04-28 23:23:13 -0600 )edit

Question Tools

4 followers

Stats

Asked: 2016-04-14 00:11:20 -0600

Seen: 4,900 times

Last updated: May 02 '16