ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Setting default tolerance on Global Planner with Move Base [closed]

asked 2016-07-11 09:07:50 -0600

emielke gravatar image

Hey, I am trying to set the default tolerance on the GlobalPlanner using move_base for a simulation I am doing with a husky. The key behavior I am looking for is that if I give the husky a goal that is in a known obstacle, it will use the default tolerance parameter to replan to a point that is not in an obstacle. I had success in this endeavor using NavfnROS as the planner and setting the default tolerance, but the behavior of NavfnROS is not what I want, it's very unreliable and the husky often stops 4 or 5 times along the way to a goal.

My problem is that when I set the default_tolerance parameter using the GlobalPlanner (using the same method I used to set it with the NavfnROS) is that the planner won't find a valid plan if I set a goal in an obstacle. I have included below the launch file I am using, with the portion of interest being the move_base launch include, as well as the .yaml file I am using to specify the parameters I want to use.

launch file portion:

<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">

<param name="base_global_planner" value="$(arg base_global_planner)"/>
<rosparam file="$(find husky_nav)/config/global_planner.yaml" command="load"/>
<param name="base_local_planner" value="$(arg base_local_planner)"/>  
<rosparam file="$(find husky_nav)/config/draper_local_planner.yaml" command="load"/>

<!-- observation sources located in costmap_common.yaml -->
<rosparam file="$(find husky_nav)/config/costmap_common.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find husky_nav)/config/costmap_common.yaml" command="load" ns="local_costmap" />

<param name="global_costmap/robot_base_frame" value = "$(arg tf_prefix)/base_link" if="$(arg use_tf_prefix)"/>
<param name="global_costmap/robot_base_frame" value = "base_link" unless="$(arg use_tf_prefix)"/>

<param name="local_costmap/robot_base_frame" value = "$(arg tf_prefix)/base_link" if="$(arg use_tf_prefix)"/>
<param name="local_costmap/robot_base_frame" value = "base_link" unless="$(arg use_tf_prefix)"/>

<!-- local costmap, needs size -->
<rosparam file="$(find husky_nav)/config/costmap_local.yaml" command="load" ns="local_costmap" />
<param name="local_costmap/width" value="10.0"/>
<param name="local_costmap/height" value="10.0"/>
<param name="local_costmap/global_frame" value="/map"/>

<!-- static global costmap, static map provides size -->
<rosparam file="$(find husky_navigation)/config/costmap_global_static.yaml" command="load" ns="global_costmap" unless="$(arg no_static_map)"/>

<!-- global costmap with laser, from odom_navigation_demo -->
<rosparam file="$(find husky_nav)/config/costmap_global_laser.yaml" command="load" ns="global_costmap" if="$(arg no_static_map)"/>
<param name="global_costmap/width" value="100.0" if="$(arg no_static_map)"/>
<param name="global_costmap/height" value="100.0" if="$(arg no_static_map)"/>
<param name="global_costmap/global_frame" value="/map"/>

global_planner.yaml file GlobalPlanner: default_tolerance: 0.5

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by emielke
close date 2016-08-02 13:49:01.901858

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-07-13 02:11:44 -0600

Arwen gravatar image

So I looked up the global planner source code in the GitHub and I found the problem.

I checked the default_tolerance parameter in the code. As you can see there is a default_tolerance_ parameter which is read from parameter server.

    private_nh.param("default_tolerance", default_tolerance_, 0.0);

Afterwards I looked up the usages of this parameter. There's only a single line that uses this parameter:

    return makePlan(start, goal, default_tolerance_, plan);

I dug further in ...

    bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal, double tolerance, std::vector<geometry_msgs::PoseStamped>& plan)

Unfortunately the tolerance parameter in makePlan doesn't have any usages at all. which means changing this parameter won't change the behavior of the global planner.

I didn't fully check your parameters but they seem fine. I think with a little modification in the global planner source code you'll get the result you want.

edit flag offensive delete link more

Comments

Perfect! I was hoping I would be able to solve this without any alterations, but it looks like I will. Thanks!

emielke gravatar image emielke  ( 2016-07-13 06:57:15 -0600 )edit

Anytime. Just let me know if you needed more help.

Arwen gravatar image Arwen  ( 2016-07-13 08:51:43 -0600 )edit

Hey, did you finally implement this? Im in need of the same thing.

juanlu gravatar image juanlu  ( 2017-04-27 06:24:54 -0600 )edit

Yes I did, I ended up having to write my own algorithm in global_planner to basically backtrack the goal point any time it was in an obstacle. I don't have enough room here or points ot reopen the question, if you want you could open a new question and I could answer it.

emielke gravatar image emielke  ( 2017-04-27 09:48:26 -0600 )edit
juanlu gravatar image juanlu  ( 2017-04-27 11:50:00 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2016-07-11 09:07:50 -0600

Seen: 2,252 times

Last updated: Jul 13 '16