[ros-users] Navigation Stack: the robot rotates most of the time after receiving a goal

Eitan Marder-Eppstein eitan at willowgarage.com
Mon Sep 20 17:37:00 UTC 2010


Xiaojun,

On Mon, Sep 20, 2010 at 6:14 AM, clarkwu <wu.xiaojun at gmail.com> wrote:

>
> Thank Wim and brian for pointing out the problems. Here are some updates:
>
> Wim's analysis is totally right,
> (1) for rotation, the odometry is 1 second delayed than the laser data;
> this
> behavior is traced back and the subroutine for gyro reading is found the
> cause for it. We wrongly used the function flush() under pyserial. After
> changed to flushImport(), the gyro readings now update fast enough.
> (2) for forward motion, the odometry drift is caused by wrong coefficients
> in forward kinematics matrix,which has also been corrected.
>
> With the above corrections, we tested the navigation in our office again.
> The result shows the navigation is almost fine, except two points:
> (1) the robot rotates suddenly during the movement, which appears too
> frequently. Please refer to the following youtube link:
> http://www.youtube.com/watch?v=MXvEcovi3f8
>
> (2) Observed from rviz window, there is an accumulative deviation between
> the laser scan points and the map. Please also refer to the youtube link:
> http://www.youtube.com/watch?v=roAMPNqg0k4
>
> For point (1), we are guessing that it might be due to the robot self
> load/high CG position, and the motors are not powerfull enough to drive the
> robot when quite small ratation speed is issued by the planner. When the
> angular difference is accumulated to certain extent, the PID controllers
> within the motor controller will boost the driving current and thus the
> sudden rotation (we have a setting for min_in_place_rotational_vel: 0.5,
> but
> seems not optimal).
>

Its possible that this is the case. Have you tried commanding similar
velocities using a joystick to see what the minimum angular speed that can
be commanded is? Other than setting min_in_place_rotational_vel to this
value, or improving the ability of the base to handle smaller velocities,
I'm not sure there's a great solution to this. You should make sure that you
set the acceleration limits for the base_local_planner in accordance with
your robot, this may help a bit with the jerk. See:
http://www.ros.org/wiki/base_local_planner#Robot_Configuration_Parameters


>
> For point (2), we have no idea about it. Is the AMCL supposed to correct
> the
> robot position?
>

AMCL will attempt to correct for the robot's position. However, if memory
serves me, the default configuration for AMCL assumes that you have pretty
good odometry. It might help you to play around with some of the parameters
that control how much to trust the estimate from odometry which might let
AMCL use the laser more heavily to snap things back into place. Relevant
parameters are documented here: http://www.ros.org/wiki/amcl#Parameters. Do
you experience much drift when you drive the robot 10 meters forward in the
odometric frame and look at accumulated laser scans?

Hope this helps,

Eitan


>
> Your further suggestions are greatly welcome.
>
> xiaojun
>
>
>
>
> --
> View this message in context:
> http://ros-users.122217.n3.nabble.com/Navigation-Stack-the-robot-rotates-most-of-the-time-after-receiving-a-goal-tp1471418p1528873.html
> Sent from the ROS-Users mailing list archive at Nabble.com.
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100920/8b5a7917/attachment-0003.html>


More information about the ros-users mailing list