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

Wim Meeussen meeussen at willowgarage.com
Fri Sep 17 14:36:03 UTC 2010


Hi xiaojun,

That video was very helpful! I see two problems with your odometry:

1) Your laser data gets timestamps that are about 1 second in the
future relative the the timestamps of your odometry. You can see this
very well when the robot rotates: the total angle rotated from the
beginning to the end of the rotation is correct, but during the robot
motion you see an offset between laser and odometry. So when you start
rotating, you create an offset, and when you stop rotating this offset
disappears. When you rotate the robot in the other direction, you
should also see an offset in the other direction.

2) Your wheel odometry is poorly calibrated for forward motion. When
you drive forward, you see the laser scan continuously drift forward.
This is because the odometry is reporting that the robot is driving a
longer distance than is actually did. When you drive the robot
backwards, the laser scan drifts backwards again for the same reason.

Hope this helps,

Wim



On Fri, Sep 17, 2010 at 2:44 AM, clarkwu <wu.xiaojun at gmail.com> wrote:
>
> Hi, Eitan and Brian,
>
> I did some further tests
> (1) verify odometry
> run ros with map off and amcl unloaded; in rviz, set both fixed frame and
> target frame to odom, laser scan decay = 0; drive robot with joystick.
> Here is what I observed in rviz window: when the robot moves forward
> following operation cmd from joystick, the laser scan points also move
> forward together with the robot, rather than staying statically in the field
> (which is supposed to be); and so does when rotating.
>
> A video clip is provided for reference:
> http://www.youtube.com/watch?v=LRxrLVh59AY
>
> What could be the reason for this phenomenon? I double checked the odometry
> publishing and tf between base_link/laser, yet can not find out.
>
> (2)
> Previously, a Fitpc-2 is put onboard the robot and running ros with
> robot-config & move_base, while rviz is running on a seperate laptop.
> I replaced the Fitpc with a third laptop with duo-core cpu, and ran the test
> again. All the symptoms are still there. So I think CPU over-load is not the
> reason.
>
> any hints?
>
> thanks
> 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-tp1471418p1516467.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
>



-- 
--
Wim Meeussen
Willow Garage Inc.
<http://www.willowgarage.com)



More information about the ros-users mailing list