diff --git a/moveit_core/package.xml b/moveit_core/package.xml index 76dd4b5596..15e7fd5603 100644 --- a/moveit_core/package.xml +++ b/moveit_core/package.xml @@ -41,13 +41,7 @@ libfcl-dev moveit_common moveit_msgs - + liboctomap-dev octomap_msgs osqp_vendor pluginlib diff --git a/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp b/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp index 955e66d09d..5997f1cadf 100644 --- a/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp +++ b/moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp @@ -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& 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& 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. @@ -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 executor = std::make_shared(); @@ -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>(), py::arg("config_dict") = py::none(), py::arg("provide_planning_service") = true, diff --git a/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp b/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp index 0eec42dd18..1df36f6a0c 100644 --- a/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp +++ b/moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp @@ -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. diff --git a/moveit_ros/occupancy_map_monitor/package.xml b/moveit_ros/occupancy_map_monitor/package.xml index 6ba31b2f19..21fba78c5c 100644 --- a/moveit_ros/occupancy_map_monitor/package.xml +++ b/moveit_ros/occupancy_map_monitor/package.xml @@ -26,13 +26,7 @@ rclcpp moveit_core moveit_msgs - + liboctomap-dev pluginlib tf2_ros geometric_shapes