Skip to content

Commit 6d376fb

Browse files
committed
Connect: Relax validity check of reached end state
1 parent 0fed09d commit 6d376fb

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

core/src/stages/connect.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ Connect::Connect(const std::string& name, const GroupPlannerVector& planners) :
5757

5858
auto& p = properties();
5959
p.declare<MergeMode>("merge_mode", WAYPOINTS, "merge mode");
60-
p.declare<double>("max_distance", 1e-4,
60+
p.declare<double>("max_distance", 1e-2,
6161
"maximally accepted joint configuration distance between trajectory endpoint and goal state");
6262
p.declare<moveit_msgs::Constraints>("path_constraints", moveit_msgs::Constraints(),
6363
"constraints to maintain during trajectory");

0 commit comments

Comments
 (0)