Skip to content

Commit

Permalink
Connect: Relax validity check of reached end state
Browse files Browse the repository at this point in the history
Looks like ROS2 uses a more relaxed goal constraint threshold than ROS1.
For this reason, all end states reached by Connect solutions of pick+place demo
are rejected. This commit relaxes the max_distance threshold of Connect as well.
  • Loading branch information
rhaschke committed Mar 13, 2024
1 parent e1b891b commit c3a69ab
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion core/src/stages/connect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ Connect::Connect(const std::string& name, const GroupPlannerVector& planners) :

auto& p = properties();
p.declare<MergeMode>("merge_mode", WAYPOINTS, "merge mode");
p.declare<double>("max_distance", 1e-4, "maximally accepted distance between end and goal sate");
p.declare<double>("max_distance", 1e-2, "maximally accepted distance between end and goal sate");
p.declare<moveit_msgs::msg::Constraints>("path_constraints", moveit_msgs::msg::Constraints(),
"constraints to maintain during trajectory");
properties().declare<TimeParameterizationPtr>("merge_time_parameterization",
Expand Down

0 comments on commit c3a69ab

Please sign in to comment.