[ros-users] Navigation stack not working

Eitan Marder-Eppstein eitan at willowgarage.com
Mon Sep 20 19:05:49 UTC 2010


Eric,

Wow... unknown_cost_value should not have been in that section. I fixed
that. Also, it turns out that if you specify a 0 character in our
documentation template for a default value... its just ignored. So, I've
changed it to "0"... which looks a little goofy but at least it shows up.

Thanks for pointing this out... sorry it was placed so poorly.

The map_server doesn't actually specify what cells to consider unknown, so
its not really like the costmap is overwriting a parameter set elsewhere.
Interpretation of a cell as occupied, unknown, or free actually happens at
the costmap level.

Sorry again for the confusion,

Etian

On Mon, Sep 20, 2010 at 11:40 AM, Eric Perko <wisesage5001 at gmail.com> wrote:

> Eitan,
>
> I did not set that, as the note on that page says "The following parameters
> are overwritten if "static_map" is set to true" and I had static_map set to
> true. Is this not the case? Also, is the default value 0? It isn't specified
> on that documentation page. It might be helpful to separate the
> documentation such that it specifies not only the default value for
> overwritten parameters, but the value that it overwrites with as well
> (obvious for width or height, but not so much for unknown_cost_value, which
> I would have assumed would match the unknown cost value from map_server).
>
> - Eric
>
>
> On Mon, Sep 20, 2010 at 2:33 PM, Eitan Marder-Eppstein <
> eitan at willowgarage.com> wrote:
>
>> Eric,
>>
>> On Mon, Sep 20, 2010 at 11:19 AM, Eric Perko <wisesage5001 at gmail.com>wrote:
>>
>>> Eitan,
>>>
>>> On Mon, Sep 20, 2010 at 1:49 PM, Eitan Marder-Eppstein <
>>> eitan at willowgarage.com> wrote:
>>>
>>>> Prasad,
>>>>
>>>> Sorry for joining the discussion a bit late.
>>>>
>>>> A couple of things:
>>>>
>>>> 1) The voxel grid tracks unknown space, but its not published in the
>>>> visualization of the grid. It was just too many cells to render. If you want
>>>> to see the 2D projection of unknown space in the voxel grid, you can
>>>> subscribe to the unknown_space topic of the relevant costmap.
>>>>
>>>
>>> Is this true even if the information comes from the static map? I'm 99%
>>> sure we saw all of the unknown space in the static map be reported on the
>>> /obstacles topic as an obstacle; even after playing around with some of the
>>> parameters for the voxel grid that had to do with unknown space, we still
>>> had that problem. This was using a map that came from GMapping and the
>>> OccupancyGrid from map_server seemed to have plenty of -1's in it (so it did
>>> have the proper thresholds). Needless to say, seeing the majority of a
>>> 4000x4000 map all reported as obstacle is a bit intensive...
>>>
>>
>> Did you set the unknown_cost_value parameter? (
>> http://www.ros.org/wiki/costmap_2d#Map_management_parameters). If this is
>> set, and your costmap is tracking unknown space, you should be able to get
>> the costmap to load unknown cells from the static map. If that's not the
>> case, then its a bug in the costmap that I need to track down. Leaving the
>> unknown_cost_value parameter at zero does default to unknown cells being set
>> to occupied in the costmap, so its possible that's what was happening to
>> you.
>>
>> Let me know how it goes,
>>
>> Eitan
>>
>>
>>>
>>> - Eric
>>>
>>>
>>>>
>>>>
>>>
>>>> 2) Publishing visualization information from very large maps can slow
>>>> the system down. As Eric suggested, setting publish_frequency to 0 for the
>>>> global_costmap should help things.
>>>>
>>>>  3) Changing the update_frequency from 5.0Hz to 8.0Hz actually makes the
>>>> map update more frequently so I'm not sure why this resolved anything for
>>>> you.
>>>>
>>>
>>>
>>> 4) For large maps, on some machines, I can see it taking some time for
>>>> AMCL to start up. Do the errors your experiencing go away consistently after
>>>> AMCL is successfully up and running?
>>>>
>>>> Hope all is well,
>>>>
>>>> Eitan
>>>>
>>>> On Mon, Sep 20, 2010 at 4:07 AM, Prasad Dixit <abhimohpra at gmail.com>wrote:
>>>>
>>>>>
>>>>> Hello Eric,
>>>>> I have changed the update rate from 5.0 to 8.0.
>>>>> Though It is taking lot of time initially to load the map and
>>>>> configuring
>>>>> likehood model; it worked finally..
>>>>> Is it something because i have not specified position in AMCL? Is this
>>>>> taking lot of time to spread initial particles and get exact global
>>>>> position
>>>>> of robot in the map?
>>>>> OR is it completely related to hardware which i should update it
>>>>> finally...??
>>>>> - Prasad
>>>>> --
>>>>> View this message in context:
>>>>> http://ros-users.122217.n3.nabble.com/Navigation-stack-not-working-tp1519053p1528384.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
>>>>>
>>>>
>>>>
>>>> _______________________________________________
>>>> ros-users mailing list
>>>> ros-users at code.ros.org
>>>> https://code.ros.org/mailman/listinfo/ros-users
>>>>
>>>>
>>>
>>> _______________________________________________
>>> ros-users mailing list
>>> ros-users at code.ros.org
>>> https://code.ros.org/mailman/listinfo/ros-users
>>>
>>>
>>
>> _______________________________________________
>> ros-users mailing list
>> ros-users at code.ros.org
>> https://code.ros.org/mailman/listinfo/ros-users
>>
>>
>
> _______________________________________________
> 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/de4bab41/attachment-0003.html>


More information about the ros-users mailing list