Christian,<div><br></div><div>A couple of things:</div><div><br></div><div>* The carrot_planner is, most likely, not what you want. All it does is seed the local planner with a point that lies on the straight line between the robot and the specified goal point that is in free space. This can make the local planner susceptible to local minima and will often fail to produce feasible plans. We use the carrot planner for things like people following where you are guaranteed that your goal point is very close to the robot. If you want a planner that will produce global plans that can be followed exactly (or at least close to exactly), I'd suggest checking out the sbpl_lattice_planner package as Sachin mentioned. The caveat here is that the code is still experimental, so you should expect the same level of documentation and testing that something like navfn has.</div>
<div><br></div><div>* As I mentioned to Eric, if you want a local planner that just attempts to follow a global path, you can check out the pose_follower package. I've only used it with a holonomic robot, so there's no guarantee that it'll do what you want, but it would be a quick thing to check.</div>
<div><br></div><div>* The local planner exists for two reasons. The first is that navfn only uses the inscribed circle of the robot to create a plan, which means that the global plan may not actually be feasible for the robot, and additional planning that takes the full footprint into account is required. The second is that global planning can take some time and a local planner is needed to make sure that the robot doesn't hit anything at a fairly high rate. If you had a global planner that was very fast and took the kinematics and dynamics of the robot into account, only a very simplistic local planner would be needed. Unfortunately, navfn is a planner which requires a local planner that has more freedom to break from the global path for things to work well.</div>
<div><br></div><div>* I'll try to take a look at the simulation you set up sometime in the next day or two.</div><div><br></div><div>Hope all is well,</div><div><br></div><div>Eitan</div><div><br><div class="gmail_quote">
On Tue, Sep 7, 2010 at 9:41 AM, Christian Verbeek <span dir="ltr"><<a href="mailto:verbeek@servicerobotics.eu">verbeek@servicerobotics.eu</a>></span> wrote:<br><blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex;">
 Eitan,<br>
<br>
After some more hours playing I found that all the pain comes from the<br>
base_local_planner. This is a powerful building block, but it does not<br>
address my needs.<br>
<br>
The plan produced by the carrot_planner is looking good all the time and<br>
what I need is not a local planner but something just eating up the<br>
global plan. If there is an obstacle along the global plan than the<br>
robot should stop and after a while with the obstacle in the global<br>
costmap replan and follow the new global plan. After all I am missing<br>
the idea behind the local planner with a perfect global plan and<br>
obstacles also be handled within the global costmap.<br>
<br>
Regards<br>
<font color="#888888">Christian<br>
</font><div><div></div><div class="h5"><br>
_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
</div></div></blockquote></div><br></div>