38 #include <pybind11/pybind11.h>
39 #include <pybind11/stl.h>
48 m.doc() =
"The planning scene represents the state of the world and the robot, "
49 "and can be used for collision checking";
51 py::class_<PlanningScene, PlanningScenePtr>(m,
"PlanningScene")
52 .def(py::init<const moveit::core::RobotModelConstPtr&, const collision_detection::WorldPtr&>(),
53 py::arg(
"robot_model"), py::arg(
"world") = std::make_shared<collision_detection::World>())
54 .def(
"checkSelfCollision",
55 py::overload_cast<const collision_detection::CollisionRequest&, collision_detection::CollisionResult&>(
57 .def(
"checkSelfCollision",
61 .def(
"checkCollision",
62 py::overload_cast<const collision_detection::CollisionRequest&, collision_detection::CollisionResult&>(
64 .def(
"checkCollision",
71 .def(
"isStateConstrained",
72 py::overload_cast<const moveit_msgs::RobotState&, const kinematic_constraints::KinematicConstraintSet&, bool>(
74 py::arg(
"state"), py::arg(
"constr"), py::arg(
"verbose") =
false)
77 py::overload_cast<const moveit::core::RobotState&, const kinematic_constraints::KinematicConstraintSet&, bool>(
79 py::arg(
"state"), py::arg(
"constr"), py::arg(
"verbose") =
false)
80 .def(
"isStateConstrained",
81 py::overload_cast<const moveit_msgs::RobotState&, const moveit_msgs::Constraints&, bool>(
83 py::arg(
"state"), py::arg(
"constr"), py::arg(
"verbose") =
false)
84 .def(
"isStateConstrained",
85 py::overload_cast<const moveit::core::RobotState&, const moveit_msgs::Constraints&, bool>(
87 py::arg(
"state"), py::arg(
"constr"), py::arg(
"verbose") =
false)
89 py::return_value_policy::reference)
94 py::arg(
"state"), py::arg(
"group"), py::arg(
"verbose") =
false)
98 py::arg(
"state"), py::arg(
"group"), py::arg(
"verbose") =
false)
100 py::overload_cast<const moveit_msgs::RobotState&, const moveit_msgs::Constraints&, const std::string&, bool>(
102 py::arg(
"state"), py::arg(
"constr"), py::arg(
"group"), py::arg(
"verbose") =
false)
104 py::overload_cast<const moveit::core::RobotState&, const moveit_msgs::Constraints&, const std::string&, bool>(
106 py::arg(
"state"), py::arg(
"constr"), py::arg(
"group"), py::arg(
"verbose") =
false)
110 py::arg(
"state"), py::arg(
"constr"), py::arg(
"group"), py::arg(
"verbose") =
false)