Expose argument of PipelinePlanner's constructor to Python (#462)

This commit is contained in:
VideoSystemsTech 2023-05-16 14:32:17 +02:00 committed by GitHub
parent d1a6916206
commit dee73b2dde
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

View File

@ -39,6 +39,7 @@
#include <moveit_msgs/WorkspaceParameters.h>
namespace py = pybind11;
using namespace py::literals;
using namespace moveit::task_constructor;
using namespace moveit::task_constructor::solvers;
@ -79,7 +80,7 @@ void export_solvers(py::module& m) {
.property<double>("goal_orientation_tolerance", "float: Tolerance for reaching orientation goals")
.property<bool>("display_motion_plans", "bool: Publish generated solutions via a topic")
.property<bool>("publish_planning_requests", "bool: Publish motion planning requests via a topic")
.def(py::init<>());
.def(py::init<const std::string&>(), "pipeline"_a = std::string("ompl"));
properties::class_<JointInterpolationPlanner, PlannerInterface>(
m, "JointInterpolationPlanner",