[ros-users] Odom in rviz

Eitan Marder-Eppstein eitan at willowgarage.com
Mon Jan 24 18:59:56 UTC 2011


Abhy,

On Mon, Jan 24, 2011 at 10:04 AM, abhy <abhy.12354 at gmail.com> wrote:

>
> Thanks for the clarification. So, going forward is it helping AMCL to
> localize robot in the world?
>

Yes, odometry helps AMCL to localize the robot in the world and, if you
don't have very good odometry, AMCL will likely give you bad pose estimates.


>
> I am asking this because, after building a map we tried to set a
> destination
> for the robot. We could see global plan is properly set but robot is not
> following a local plan.
> For e.g.: If robot physically pointing towards say north side (sensor north
> side)  but in rviz it is not showing properly oriented and not even at the
> same location in the map where it is physically located. so, position and
> orientation both are differing to the real robot and while moving it is
> giving jerks and drops the plan since local planner is getting failed. It
> seems it is some localization related stuff which is not allowing robot to
> get localize properly into the map inspite of giving initial x,y, theta
> values in amcl parameters. so, we thought it can be related to /odom.
>
> Is there any settings we have to follow other than this to get localize
> robot in to the world and move as per the plan?
>

Before you work on tweaking the navigation stack, you'll want to make sure
that both your odometry and AMCL-localization are working well. The first
thing to check is odometry. There are a number of tests you can perform to
see how well your odometry is working:

Test 1: Open up rviz and make sure that you're subscribed to the laser scan
topic for your robot. Next, set the decay time to something like 30 seconds.
Perform an in-place rotation with the robot and look at the laser scans. If
odometry is fairly accurate, you should see scans from the previous rotation
overlap with those generated on the current rotation. You'll want to do this
in an area where you have distinctive features in your laser scan.

Test 2: Set up rviz the same way as the previous test. Point the robot at a
wall and drive it towards it. With good odometry, the wall should stay in
about the same place as the robot moves towards it. If you see a lot of
movement in the positions of the scans relative to the wall that means
odometry is poor.

Test 3: Drive the robot straight down a hallway. The laser scans of the
hallway should stay straight. If you see them move a lot, it means your
odometry is poor.

Once you've performed these tests, you should have a pretty good idea of
whether or not your odometry is to blame for the poor localization of the
robot. Then, we can move on to AMCL and tuning the navigation stack..

Hope this helps,

Eitan


>
> -Abhy
> --
> View this message in context:
> http://ros-users.122217.n3.nabble.com/Odom-in-rviz-tp2320561p2321499.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/20110124/f396e2c7/attachment-0003.html>


More information about the ros-users mailing list