Nitin,

On Mon, Aug 9, 2010 at 11:09 AM, nitinDhiman <nitinkdhiman@gmail.com> wrote:

Thanks Eitan,
It did help.

I want to combine an occupancy grid, generated by non-ROS algorithm setup,
with Costmap2D grid in some another node and later use this new grid for
path planning purpose. I agree on point that if vision sensor can also
publish point cloud then Costmap2D can take over from there. But it may be
good to have sth like this where point cloud publication is not possible.

In that case you could write code to take the GridCell messages being published over ROS by the costmap (see http://www.ros.org/wiki/costmap_2d#Published_Topics) and combine them with your custom grid in some other node. You can get the resolution of the cells by looking at the cell_width and cell_height fields of the nav_msgs/GridCells message.

About occupancy grid in ROS. It is in for of cell and each cell have
resolution as meter/cell. I have impression that ROS always expect this
resolution to be small. Do we deal with cases where multiple laser scans are
passing through a cell. Then how it is dealt? For example, five laser beams
pass through a cell and 2 represent obstruction while 3 do not. How this is
modelled in Costmap2D?

The costmap lacks a probabilistic model so it will just take the latest observation. We did this for efficiency reasons, and haven't found it to be a huge issue... though you could write a version of the costmap that deals with things differently.
 

About path planning for rectangular robots, I am hoping to get an field A*
based implementation in place.  I hope it will suffice.  I will also have a
look at SBPL planner. Has someone tried using CHOMP?

I don't think that anyone has used CHOMP for the base, though it has been used for our robot's arms.
 

About move_base having one node only. Am I correct if I say CostMap
generation using CostMap2DROS, global and local path planning are happening
on this move_base node? If yes, Isn't it is loaded. One would probably like
to take out say path planning as different node to other processor ! Or
Advantage of having all of them in one place is "there are no network
delays" ?

You're right that a lot of things are happening in the move_base node and that its primarily done to avoid network delays. Major operations within the node are threaded, so it can take advantage of something like a multi-core machine, but you can't take the components contained in the move_base node and distribute them across multiple machines. In the future, I'd like to rewrite much of move_base using a nodelet based approach that will allow you to configure navigation components to run in the same process or across the network, but I'm not sure exactly when I'll get around to that.

Hope all is well,

Eitan
 

thank you
nitin




--
View this message in context: http://ros-users.122217.n3.nabble.com/costmap-grids-tp1051168p1060179.html
Sent from the ROS-Users mailing list archive at Nabble.com.

------------------------------------------------------------------------------
This SF.net email is sponsored by

Make an app they can't live without
Enter the BlackBerry Developer Challenge
http://p.sf.net/sfu/RIM-dev2dev
_______________________________________________
ros-users mailing list
ros-users@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/ros-users
_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users