@@ -60,8 +60,9 @@ void initMoveitPy(py::module& m)
60
60
The MoveItPy class is the main interface to the MoveIt Python API. It is a wrapper around the MoveIt C++ API.
61
61
)" )
62
62
63
- .def (py::init ([](const std::string& node_name, const std::vector<std::string>& launch_params_filepaths,
64
- const py::object& config_dict, bool provide_planning_service) {
63
+ .def (py::init ([](const std::string& node_name, const std::string& name_space,
64
+ const std::vector<std::string>& launch_params_filepaths, const py::object& config_dict,
65
+ bool provide_planning_service) {
65
66
// This section is used to load the appropriate node parameters before spinning a moveit_cpp instance
66
67
// Priority is given to parameters supplied directly via a config_dict, followed by launch parameters
67
68
// and finally no supplied parameters.
@@ -106,7 +107,7 @@ void initMoveitPy(py::module& m)
106
107
.arguments (launch_arguments);
107
108
108
109
RCLCPP_INFO (getLogger (), " Initialize node and executor" );
109
- rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared (node_name, " " , node_options);
110
+ rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared (node_name, name_space , node_options);
110
111
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor =
111
112
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
112
113
@@ -133,7 +134,7 @@ void initMoveitPy(py::module& m)
133
134
134
135
return moveit_cpp_ptr;
135
136
}),
136
- py::arg (" node_name" ) = " moveit_py" ,
137
+ py::arg (" node_name" ) = " moveit_py" , py::arg ( " name_space " ) = " " ,
137
138
py::arg (" launch_params_filepaths" ) =
138
139
utils.attr (" get_launch_params_filepaths" )().cast <std::vector<std::string>>(),
139
140
py::arg (" config_dict" ) = py::none (), py::arg (" provide_planning_service" ) = true ,
0 commit comments