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,