[ros-users] Navigation stack not working

Eitan Marder-Eppstein eitan at willowgarage.com
Tue Sep 21 17:28:16 UTC 2010


Prasad,

On Tue, Sep 21, 2010 at 12:04 AM, Prasad Dixit <abhimohpra at gmail.com> wrote:

>
> Thank you Brian, Eitan, Eric for helping me out.
>
> some updates i observed while testing further:
>
> 1. It is now taking 4000 X 4000 sized map properly, initially it takes lot
> of time to load the entire stack. Here, I saw weired behavior, like, this
> time i again changed update_frequency to 1 and publish_frequency to 0 which
> worked absolutely fine. This did not work for me last time.
>

I'm not sure exactly what you mean here when you say "weird behavior," but
one thing that you should remember about setting update_frequency lower is
that it will affect how often obstacles are put into the costmap. With a
setting of 1.0Hz, this means you'll only take in new obstacle information
once a second which may be problematic depending on what dynamic obstacles
exist in your environment. I'm also surprised that you had success with this
setting only the second time you tried it, and not the first, but I'm glad
things are working.


>
> 2. As per your remarks - yes, its taking some time to load AMCL and MAP all
> together but after that it works smoothly.
> It shows some messages at start after map load but then later it stops
> giving those, may be since i have set publish_frequency to 0.
>
>  ********
> [ WARN] [1285046609.189924589]: Costmap2DROS transform timeout. Current
> time: 1285046609.1898, global_pose stamp: 1285046608.8674, tolerance:
> 0.3000
> [ WARN] [1285046609.690016886]: Costmap2DROS transform timeout. Current
> time: 1285046609.6899, global_pose stamp: 1285046609.3679, tolerance:
> 0.3000
> [ WARN] [1285046609.789254073]: Costmap2DROS transform timeout. Current
> time: 1285046609.7891, global_pose stamp: 1285046609.3679, tolerance:
> 0.3000
> [ WARN] [1285046609.890064495]: Costmap2DROS transform timeout. Current
> time: 1285046609.8899, global_pose stamp: 1285046609.3679, tolerance:
> 0.3000
> [ WARN] [1285046609.999240402]: Costmap2DROS transform timeout. Current
> time: 1285046609.9991, global_pose stamp: 1285046609.5634, tolerance:
> 0.3000
> [ WARN] [1285046797.412466274]: Costmap2DROS transform timeout. Current
> time: 1285046797.4123, global_pose stamp: 1285046797.1032, tolerance:
> 0.3000
> [ WARN] [1285046797.490019288]: Costmap2DROS transform timeout. Current
> time: 1285046797.4899, global_pose stamp: 1285046797.1032, tolerance:
> 0.3000
> [ WARN] [1285046797.589259643]: Costmap2DROS transform timeout. Current
> time: 1285046797.5891, global_pose stamp: 1285046797.1032, tolerance:
> 0.3000
> [ WARN] [1285046797.690021824]: Costmap2DROS transform timeout. Current
> time: 1285046797.6899, global_pose stamp: 1285046797.1032, tolerance:
> 0.3000
> [ WARN] [1285046582.296975123]: Map update loop missed its desired rate of
> 5.0000Hz... the loop actually took 5.7582 seconds
> [ WARN] [1285046582.297395444]: Costmap2DROS transform timeout. Current
> time: 12
> *********
> Can i solve this slow behavior after updating hardware?
>

Updating hardware will help here, but you'll likely always get a few
warnings on startup. Eventually, I should get around to being more
intelligent about printing that warning out. Sometimes.... its really
important and can call attention to serious problems in the system, but, at
startup in particular, its almost expected.


>
> 3. Brian: I am using 0.1.4-33 Navigation stack. Am i suppose to try some
> new
> experimental stack?
>

The version number "0.1.4" doesn't make sense. Can you "roscd navigation"
and look at the version number in the CMakeLists.txt  file and list that.


>
> 4. My tf_monitor gives me the output as below
> Node: /amcl 10.0502 Hz, Average Delay: -0.0153442 Max Delay: 0.145252 <==
> which is in negative
> Node: /eskorta_odom 22.022 Hz, Average Delay: 0.000921226 Max Delay:
> 0.0214084
> Node: /eskorta_state 30.0514 Hz, Average Delay: 0.0180185 Max Delay:
> 0.0565425
> Is it fine to have negative delay? -  i am not able to figure it out since
> this is my pre-hardware testing.
>

I'm not sure why the average delay would be negative. I'll let someone who
knows more chime in on this.


>
> 5. I also saw your conversation about unknown_cost_value which is quite
> useful for user like me. Just extending this conversation bit i want to
> know
> (I had raised this question sometime back in some other thread also) --
> In case we have a stair case scenario where we want to avoid robot to go
> and
> to get fall down. We also can not put any obstruction in between..so can we
> take the advantage of voxel grid's behavior of showing obstacle as an
> unknown space. Can we plan to treat stair case start as an unknown space
> while mapping itself (by not throwing laser on wall behind stair case)? so
> as, for future reference robot will  always treat it is as unknown space
> (obstacle) and will not traverse there.
>

The best way of doing this is to have a "sensor" that asserts that an
obstacle is observed at the stairway. Both the global and local costmaps
will have access to this information and it should, assuming the robot is
well localized, keep the robot away from dangerous areas.

Hope this helps,

Eitan


>
> Please let me know if you have any expert views on my questions
>
> - Prasad
>
> --
> View this message in context:
> http://ros-users.122217.n3.nabble.com/Navigation-stack-not-working-tp1519053p1533561.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/20100921/b3db9a9f/attachment-0003.html>


More information about the ros-users mailing list