Skip to content

Commit 7d50093

Browse files
committed
Use pybind11's smart_holder branch
1 parent 37a5b37 commit 7d50093

File tree

5 files changed

+14
-9
lines changed

5 files changed

+14
-9
lines changed

.gitmodules

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
11
[submodule "core/python/pybind11"]
22
path = core/python/pybind11
3-
url = https://github.com/rhaschke/pybind11
3+
url = https://github.com/pybind11/pybind11
44
shallow = true

core/python/pybind11

core/python/wrapper/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@ install(TARGETS ${TOOLS_LIB_NAME}
1818
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
1919
)
2020

21+
add_definitions(-DPYBIND11_USE_SMART_HOLDER_AS_DEFAULT)
2122

2223
# python_tools
2324
set(TOOLS_LIB_NAME _python_tools)

core/python/wrapper/src/core.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ void export_core(pybind11::module& m) {
7676
});
7777

7878
// clang-format off
79-
py::class_<SolutionBase, SolutionBasePtr>(m, "Solution")
79+
py::class_<SolutionBase>(m, "Solution")
8080
.def_property("cost", &SolutionBase::cost, &SolutionBase::setCost)
8181
.def_property("comment", &SolutionBase::comment, &SolutionBase::setComment)
8282
.def("toMsg", [](const SolutionBasePtr& s) {
@@ -169,10 +169,12 @@ void export_core(pybind11::module& m) {
169169
throw py::index_error();
170170
return child;
171171
}, py::return_value_policy::reference_internal)
172+
#if 0
172173
.def("__iter__", [](const ContainerBase &c) {
173174
const auto& children = c.pimpl()->children();
174175
return py::make_iterator(children.begin(), children.end());
175176
}, py::keep_alive<0, 1>()) // keep container alive as long as iterator lives
177+
#endif
176178
;
177179

178180
py::class_<SerialContainer, ContainerBase>(m, "SerialContainer")
@@ -211,18 +213,20 @@ void export_core(pybind11::module& m) {
211213
throw py::index_error();
212214
return child;
213215
}, py::return_value_policy::reference_internal)
216+
#if 0
214217
.def("__iter__", [](const Task &t) {
215218
const auto& children = t.stages()->pimpl()->children();
216219
return py::make_iterator(children.begin(), children.end());
217220
}, py::keep_alive<0, 1>()) // keep container alive as long as iterator lives
221+
#endif
218222
.def("reset", &Task::reset)
219223
.def("init", &Task::init)
220224
.def("plan", &Task::plan, py::arg("max_solutions") = 0)
221225
.def("preempt", &Task::preempt)
222-
.def("publish", [](Task& self, SolutionBasePtr& solution) {
226+
.def("publish", [](Task& self, SolutionBasePtr solution) {
223227
self.introspection().publishSolution(*solution);
224228
})
225-
.def("execute", [](const Task& self, SolutionBasePtr& solution) {
229+
.def("execute", [](const Task& self, SolutionBasePtr solution) {
226230
moveit::planning_interface::PlanningSceneInterface psi;
227231
moveit::planning_interface::MoveGroupInterface
228232
mgi(solution->start()->scene()->getRobotModel()->getJointModelGroupNames()[0]);

core/python/wrapper/src/solvers.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -16,13 +16,13 @@ void export_solvers(py::module& m) {
1616
PropertyMap& (PlannerInterface::*PlannerInterface_getPropertyMap)() = &PlannerInterface::properties;
1717

1818
// clang-format off
19-
properties::class_<PlannerInterface, PlannerInterfacePtr>(m, "PlannerInterface")
19+
properties::class_<PlannerInterface>(m, "PlannerInterface")
2020
.property<double>("max_velocity_scaling_factor")
2121
.property<double>("max_acceleration_scaling_factor")
2222
.def_property_readonly("properties", PlannerInterface_getPropertyMap, py::return_value_policy::reference_internal)
2323
;
2424

25-
properties::class_<PipelinePlanner, PipelinePlannerPtr, PlannerInterface>(m, "PipelinePlanner")
25+
properties::class_<PipelinePlanner, PlannerInterface>(m, "PipelinePlanner")
2626
.property<std::string>("planner")
2727
.property<uint>("num_planning_attempts")
2828
.property<moveit_msgs::WorkspaceParameters>("workspace_parameters")
@@ -34,12 +34,12 @@ void export_solvers(py::module& m) {
3434
.def(py::init<>())
3535
;
3636

37-
properties::class_<JointInterpolationPlanner, JointInterpolationPlannerPtr, PlannerInterface>(m, "JointInterpolationPlanner")
37+
properties::class_<JointInterpolationPlanner, PlannerInterface>(m, "JointInterpolationPlanner")
3838
.property<double>("max_step")
3939
.def(py::init<>())
4040
;
4141

42-
properties::class_<CartesianPath, CartesianPathPtr, PlannerInterface>(m, "CartesianPath")
42+
properties::class_<CartesianPath, PlannerInterface>(m, "CartesianPath")
4343
.property<double>("step_size")
4444
.property<double>("jump_threshold")
4545
.property<double>("min_fraction")

0 commit comments

Comments
 (0)