Skip to content

Commit

Permalink
Merge branch 'main' into pr-port-planning-scene-fix
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr authored Jul 11, 2024
2 parents e8224d4 + 9b3d96a commit f1c1ab4
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 18 deletions.
8 changes: 1 addition & 7 deletions moveit_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -41,13 +41,7 @@
<depend>libfcl-dev</depend>
<depend>moveit_common</depend>
<depend>moveit_msgs</depend>
<!--
Temporarily disable octomap dependency because of
version conflict. We use liboctomap-dev provided
by libfcl-dev.
See https://github.com/moveit/moveit2/issues/2862
<depend>octomap</depend>
-->
<depend>liboctomap-dev</depend>
<depend>octomap_msgs</depend>
<depend>osqp_vendor</depend>
<depend>pluginlib</depend>
Expand Down
9 changes: 5 additions & 4 deletions moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,9 @@ void initMoveitPy(py::module& m)
The MoveItPy class is the main interface to the MoveIt Python API. It is a wrapper around the MoveIt C++ API.
)")

.def(py::init([](const std::string& node_name, const std::vector<std::string>& launch_params_filepaths,
const py::object& config_dict, bool provide_planning_service) {
.def(py::init([](const std::string& node_name, const std::string& name_space,
const std::vector<std::string>& launch_params_filepaths, const py::object& config_dict,
bool provide_planning_service) {
// This section is used to load the appropriate node parameters before spinning a moveit_cpp instance
// Priority is given to parameters supplied directly via a config_dict, followed by launch parameters
// and finally no supplied parameters.
Expand Down Expand Up @@ -106,7 +107,7 @@ void initMoveitPy(py::module& m)
.arguments(launch_arguments);

RCLCPP_INFO(getLogger(), "Initialize node and executor");
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, "", node_options);
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, name_space, node_options);
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor =
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

Expand All @@ -133,7 +134,7 @@ void initMoveitPy(py::module& m)

return moveit_cpp_ptr;
}),
py::arg("node_name") = "moveit_py",
py::arg("node_name") = "moveit_py", py::arg("name_space") = "",
py::arg("launch_params_filepaths") =
utils.attr("get_launch_params_filepaths")().cast<std::vector<std::string>>(),
py::arg("config_dict") = py::none(), py::arg("provide_planning_service") = true,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -175,6 +175,15 @@ void initPlanningSceneMonitor(py::module& m)
attached_collision_object_msg (moveit_msgs.msg.AttachedCollisionObject): The attached collision object to apply to the planning scene.
)")

.def("new_planning_scene_message", &planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneMessage,
py::arg("scene"),
R"(
Called to update the planning scene with a new message.
Args:
scene (moveit_msgs.msg.PlanningScene): The new planning scene message.
)")

.def("read_only", &moveit_py::bind_planning_scene_monitor::readOnly,
R"(
Returns a read-only context manager for the planning scene.
Expand Down
8 changes: 1 addition & 7 deletions moveit_ros/occupancy_map_monitor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,7 @@
<depend>rclcpp</depend>
<depend>moveit_core</depend>
<depend>moveit_msgs</depend>
<!--
Temporarily disable octomap dependency because of
version conflict. We use liboctomap-dev provided
by moveit_core->libfcl-dev.
See https://github.com/moveit/moveit2/issues/2862
<depend>octomap</depend>
-->
<depend>liboctomap-dev</depend>
<depend version_gte="1.11.2">pluginlib</depend>
<depend>tf2_ros</depend>
<depend>geometric_shapes</depend>
Expand Down

0 comments on commit f1c1ab4

Please sign in to comment.