Skip to content

Commit dee73b2

Browse files
Expose argument of PipelinePlanner's constructor to Python (#462)
1 parent d1a6916 commit dee73b2

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

core/python/bindings/src/solvers.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include <moveit_msgs/WorkspaceParameters.h>
4040

4141
namespace py = pybind11;
42+
using namespace py::literals;
4243
using namespace moveit::task_constructor;
4344
using namespace moveit::task_constructor::solvers;
4445

@@ -79,7 +80,7 @@ void export_solvers(py::module& m) {
7980
.property<double>("goal_orientation_tolerance", "float: Tolerance for reaching orientation goals")
8081
.property<bool>("display_motion_plans", "bool: Publish generated solutions via a topic")
8182
.property<bool>("publish_planning_requests", "bool: Publish motion planning requests via a topic")
82-
.def(py::init<>());
83+
.def(py::init<const std::string&>(), "pipeline"_a = std::string("ompl"));
8384

8485
properties::class_<JointInterpolationPlanner, PlannerInterface>(
8586
m, "JointInterpolationPlanner",

0 commit comments

Comments
 (0)