sikang / mpl_ros

A ROS wrapper for trajectory planning based on motion primitives
Apache License 2.0
558 stars 148 forks source link

Questions related to map_replanner_node #9

Open Kaustav6422 opened 5 years ago

Kaustav6422 commented 5 years ago

Hello Sikang, I am trying to understand the map_replanner_node and I had the following questions related to it.

1) By using subscriber callbacks addCloudCallback() and clearCloudCallback(), we are updating the map as the bot is moving. Now, if we use the traditional local_planner/global_planner framework of ROS, we use the Lidar data to update the localmap in odom frame and the local trajectory is planned in the odom frame. But according to your code, it looks like addCloudCallback() and clearCloudCallback() is working in the global frame and updates the global map. So if I use my Lidar data, it would have to be transformed from base_frame ->odom_frame->map_frame before updating the map. Is my understanding correct ?

2) What topic should clearCloudCallback() subscribe to ? It is obvious that addCloudCallback() would subscribe to the Lidar pointcloud to update the map in it's surrounding based on it's range. What about clearCloudCallback() ? Shouldn't both callbacks subscribe to the same Lidar data topic?

3) What is the use of subtreeCallback() ?

4) At what rate is the replanner running ? It looks like planning thread is being run separately.

Thank you.

sikang commented 5 years ago

Hi, sorry for the late response. The map_replanner_node is something else instead of just ``replanner'', it is an implementation of LPA* that is used for incremental trajectory planning. Comparing to replan from scratch every time, it is computationally more efficient to keep the related parts of the old graph and update the corresponding edge costs according to the map update and further plan the trajectory based on the new graph. So the function in this node is actually designed for this planning method:

  1. it is assume the map_frame is not changing, so everything should be in the global map frame;
  2. clearCloud and addCloud are actually some test function for removing and adding points in a map;
  3. subtree is used to prune the old graph and get the sub-graph;
  4. the rate depends on the edge duration `dt', eg. 1/dt Hz. Since it is not a traditional replanner, I would not recommend to use it for normal replan. A easier way is to replan from scratch every time.

SIkang