Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Python] Added Allowed Collision Matrix to planning scene and optional planning scene during planning (backport #2387) #2479

Merged
merged 2 commits into from
Jan 23, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions moveit_py/moveit/core/planning_scene.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -29,3 +29,5 @@ class PlanningScene:
def robot_model(self) -> Any: ...
@property
def transforms(self) -> Any: ...
@property
def allowed_collision_matrix(self) -> Any: ...
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,8 @@ void init_planning_scene(py::module& m)
py::return_value_policy::move)

.def_property("transforms", py::overload_cast<>(&planning_scene::PlanningScene::getTransforms), nullptr)

.def_property("allowed_collision_matrix", &planning_scene::PlanningScene::getAllowedCollisionMatrix, nullptr,
py::return_value_policy::move)
// methods
.def("__copy__",
[](const planning_scene::PlanningScene* self) {
Expand Down
23 changes: 16 additions & 7 deletions moveit_py/src/moveit/moveit_ros/moveit_cpp/planning_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ planning_interface::MotionPlanResponse
plan(std::shared_ptr<moveit_cpp::PlanningComponent>& planning_component,
std::shared_ptr<moveit_cpp::PlanningComponent::PlanRequestParameters>& single_plan_parameters,
std::shared_ptr<moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters>& multi_plan_parameters,
std::shared_ptr<planning_scene::PlanningScene>& planning_scene,
std::optional<const moveit::planning_pipeline_interfaces::SolutionSelectionFunction> solution_selection_function,
std::optional<moveit::planning_pipeline_interfaces::StoppingCriterionFunction> stopping_criterion_callback)
{
Expand All @@ -61,7 +62,7 @@ plan(std::shared_ptr<moveit_cpp::PlanningComponent>& planning_component,
std::shared_ptr<const moveit_cpp::PlanningComponent::PlanRequestParameters> const_single_plan_parameters =
std::const_pointer_cast<const moveit_cpp::PlanningComponent::PlanRequestParameters>(single_plan_parameters);

return planning_component->plan(*const_single_plan_parameters);
return planning_component->plan(*const_single_plan_parameters, planning_scene);
}
else if (multi_plan_parameters)
{
Expand All @@ -73,25 +74,32 @@ plan(std::shared_ptr<moveit_cpp::PlanningComponent>& planning_component,
if (solution_selection_function && stopping_criterion_callback)
{
return planning_component->plan(*const_multi_plan_parameters, std::ref(*solution_selection_function),
*stopping_criterion_callback);
*stopping_criterion_callback, planning_scene);
}
else if (solution_selection_function)
{
return planning_component->plan(*const_multi_plan_parameters, std::ref(*solution_selection_function));
return planning_component->plan(*const_multi_plan_parameters, std::ref(*solution_selection_function), nullptr,
planning_scene);
}
else if (stopping_criterion_callback)
{
return planning_component->plan(*const_multi_plan_parameters,
moveit::planning_pipeline_interfaces::getShortestSolution,
*stopping_criterion_callback);
*stopping_criterion_callback, planning_scene);
}
else
{
return planning_component->plan(*const_multi_plan_parameters);
return planning_component->plan(*const_multi_plan_parameters,
moveit::planning_pipeline_interfaces::getShortestSolution, nullptr,
planning_scene);
}
}
else
{
if (planning_scene)
{
throw std::invalid_argument("Cannot specify planning scene without specifying plan parameters");
}
return planning_component->plan();
}
}
Expand Down Expand Up @@ -322,8 +330,9 @@ void init_planning_component(py::module& m)

// TODO (peterdavidfagan): improve the plan API
.def("plan", &moveit_py::bind_planning_component::plan, py::arg("single_plan_parameters") = nullptr,
py::arg("multi_plan_parameters") = nullptr, py::arg("solution_selection_function") = nullptr,
py::arg("stopping_criterion_callback") = nullptr, py::return_value_policy::move,
py::arg("multi_plan_parameters") = nullptr, py::arg("planning_scene") = nullptr,
py::arg("solution_selection_function") = nullptr, py::arg("stopping_criterion_callback") = nullptr,
py::return_value_policy::move,
R"(
Plan a motion plan using the current start and goal states.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ planning_interface::MotionPlanResponse
plan(std::shared_ptr<moveit_cpp::PlanningComponent>& planning_component,
std::shared_ptr<moveit_cpp::PlanningComponent::PlanRequestParameters>& single_plan_parameters,
std::shared_ptr<moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters>& multi_plan_parameters,
std::shared_ptr<planning_scene::PlanningScene>& planning_scene,
std::optional<const moveit::planning_pipeline_interfaces::SolutionSelectionFunction> solution_selection_function,
std::optional<moveit::planning_pipeline_interfaces::StoppingCriterionFunction> stopping_criterion_callback);

Expand Down
Loading