navigation icon indicating copy to clipboard operation
navigation copied to clipboard

latch_xy_goal_tolerance parameter is not loaded

Open naoki-rapyuta opened this issue 5 years ago • 3 comments

The parameter latch_xy_goal_tolerance is not loaded when defined in a named section (typically "TrajectoryPlannerROS") as follows:

TrajectoryPlannerROS:
  ....

  latch_xy_goal_tolerance: true

The above configuration is not loaded by LatchedStopRotateController used by DWAPlannerROS.

LatchedStopRotateController constructor expects a configuration section name so that it can fetch the parameters:

LatchedStopRotateController::LatchedStopRotateController(const std::string& name) {
  ros::NodeHandle private_nh("~/" + name);
  private_nh.param("latch_xy_goal_tolerance", latch_xy_goal_tolerance_, false);

  rotating_to_goal_ = false;
}

But DWAPlannerROS declares LatchedStopRotateController as a member variable and not passing the name to the constructor. As LatchedStopRotateController accepts an empty string as the default parameter to the constructor, the configuration is not loaded from a named section (typically, "TrajectoryPlannerROS").

Current work around is to put 'latch_xy_goal_tolerance' at the root level as follows:

latch_xy_goal_tolerance: true

TrajectoryPlannerROS:
  ....

naoki-rapyuta avatar Aug 26 '19 05:08 naoki-rapyuta

I am having a similar problem where it seems to be ignoring the 'latch_xy_goal_tolerance' setting. The robot gets to the xy position, but keeps rotating once it gets there. Did you have to do any other modifications to other settings? Thanks.

jsseng avatar Sep 09 '19 16:09 jsseng

I am having a similar problem where it seems to be ignoring the 'latch_xy_goal_tolerance' setting. The robot gets to the xy position, but keeps rotating once it gets there. Did you have to do any other modifications to other settings? Thanks.

@jsseng The above config change is the only thing I did to make it work as expected.

naoki-rapyuta avatar Sep 09 '19 22:09 naoki-rapyuta

I was having the same issue - stop and rotate behavior not taking place when 'latch_xy_goal_tolerance' was set as described in the documentation (http://wiki.ros.org/base_local_planner?distro=melodic). Moving it into the global namespace as suggested by @naoki-rapyuta fixed the issue and solved what was an ongoing headache for me.

haljarrett avatar Feb 26 '20 17:02 haljarrett