We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
There was an error while loading. Please reload this page.
1 parent 721ff35 commit 0a502ceCopy full SHA for 0a502ce
core/python/bindings/src/stages.cpp
@@ -328,6 +328,11 @@ void export_stages(pybind11::module& m) {
328
)")
329
.property<stages::Connect::MergeMode>("merge_mode", "Defines the merge strategy to use")
330
.property<double>("max_distance", "maximally accepted distance between end and goal sate")
331
+ .property<moveit_msgs::Constraints>("path_constraints", R"(
332
+ Constraints_: These are the path constraints.
333
+
334
+ .. _Constraints: https://docs.ros.org/en/api/moveit_msgs/html/msg/Constraints.html
335
+ )")
336
.def(py::init<const std::string&, const Connect::GroupPlannerVector&>(),
337
"name"_a = std::string("connect"), "planners"_a);
338
0 commit comments