Skip to content

Commit

Permalink
Add path_constraints property to Connect stage
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Oct 11, 2024
1 parent 721ff35 commit 0a502ce
Showing 1 changed file with 5 additions and 0 deletions.
5 changes: 5 additions & 0 deletions core/python/bindings/src/stages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -328,6 +328,11 @@ void export_stages(pybind11::module& m) {
)")
.property<stages::Connect::MergeMode>("merge_mode", "Defines the merge strategy to use")
.property<double>("max_distance", "maximally accepted distance between end and goal sate")
.property<moveit_msgs::Constraints>("path_constraints", R"(
Constraints_: These are the path constraints.
.. _Constraints: https://docs.ros.org/en/api/moveit_msgs/html/msg/Constraints.html
)")
.def(py::init<const std::string&, const Connect::GroupPlannerVector&>(),
"name"_a = std::string("connect"), "planners"_a);

Expand Down

0 comments on commit 0a502ce

Please sign in to comment.