Skip to content

Commit 046309d

Browse files
committed
Simplify rclcpp::Node creation
Directly pass node name and namespace instead of using options.
1 parent 5ae22da commit 046309d

File tree

5 files changed

+7
-20
lines changed

5 files changed

+7
-20
lines changed

core/src/introspection.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -108,9 +108,7 @@ class IntrospectionPrivate
108108
{
109109
public:
110110
IntrospectionPrivate(const TaskPrivate* task, Introspection* self) : task_(task), task_id_(getTaskId(task)) {
111-
rclcpp::NodeOptions options;
112-
options.arguments({ "--ros-args", "-r", "__node:=introspection_" + task_id_ });
113-
node_ = rclcpp::Node::make_shared("_", task_->ns(), options);
111+
node_ = rclcpp::Node::make_shared("introspection_" + task_id_, task_->ns());
114112
executor_.add_node(node_);
115113
task_description_publisher_ = node_->create_publisher<moveit_task_constructor_msgs::msg::TaskDescription>(
116114
DESCRIPTION_TOPIC, rclcpp::QoS(2).transient_local());

core/src/stages/current_state.cpp

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -75,10 +75,7 @@ void CurrentState::compute() {
7575
scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
7676

7777
// Add random ID to prevent warnings about multiple publishers within the same node
78-
rclcpp::NodeOptions options;
79-
options.arguments(
80-
{ "--ros-args", "-r", "__node:=current_state_" + std::to_string(reinterpret_cast<std::size_t>(this)) });
81-
auto node = rclcpp::Node::make_shared("_", options);
78+
auto node = rclcpp::Node::make_shared("current_state_" + std::to_string(reinterpret_cast<std::size_t>(this)));
8279
auto client = node->create_client<moveit_msgs::srv::GetPlanningScene>("get_planning_scene");
8380

8481
auto timeout = std::chrono::duration<double>(this->timeout());

core/src/task.cpp

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -270,11 +270,8 @@ void Task::preempt() {
270270

271271
moveit::core::MoveItErrorCode Task::execute(const SolutionBase& s) {
272272
// Add random ID to prevent warnings about multiple publishers within the same node
273-
rclcpp::NodeOptions options;
274-
options.arguments(
275-
{ "--ros-args", "-r",
276-
"__node:=moveit_task_constructor_executor_" + std::to_string(reinterpret_cast<std::size_t>(this)) });
277-
auto node = rclcpp::Node::make_shared("_", options);
273+
auto node = rclcpp::Node::make_shared("moveit_task_constructor_executor_" +
274+
std::to_string(reinterpret_cast<std::size_t>(this)));
278275
auto ac = rclcpp_action::create_client<moveit_task_constructor_msgs::action::ExecuteTaskSolution>(
279276
node, "execute_task_solution");
280277
if (!ac->wait_for_action_server(0.5s)) {

visualization/motion_planning_tasks/src/remote_task_model.cpp

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -189,11 +189,8 @@ RemoteTaskModel::RemoteTaskModel(const std::string& service_name, const planning
189189
: BaseTaskModel(scene, display_context, parent), root_(new Node(nullptr)) {
190190
id_to_stage_[0] = root_; // root node has ID 0
191191
// Add random ID to prevent warnings about multiple publishers within the same node
192-
rclcpp::NodeOptions options;
193-
options.arguments({ "--ros-args", "-r",
194-
"__node:=get_solution_node_" + std::to_string(reinterpret_cast<std::size_t>(this)), "-r",
195-
"__ns:=/moveit_task_constructor/remote_task_model" });
196-
node_ = rclcpp::Node::make_shared("_", options);
192+
node_ = rclcpp::Node::make_shared("get_solution_node_" + std::to_string(reinterpret_cast<std::size_t>(this)),
193+
"/moveit_task_constructor/remote_task_model");
197194
// service to request solutions
198195
get_solution_client_ = node_->create_client<moveit_task_constructor_msgs::srv::GetSolution>(service_name);
199196
}

visualization/motion_planning_tasks/src/task_panel.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -228,9 +228,7 @@ void setExpanded(QTreeView* view, const QModelIndex& index, bool expand, int dep
228228
TaskViewPrivate::TaskViewPrivate(TaskView* view) : q_ptr(view) {
229229
setupUi(view);
230230

231-
rclcpp::NodeOptions options;
232-
options.arguments({ "--ros-args", "-r", "__node:=task_view_private" });
233-
node_ = rclcpp::Node::make_shared("_", "", options);
231+
node_ = rclcpp::Node::make_shared("task_view_private", "");
234232
exec_action_client_ = rclcpp_action::create_client<moveit_task_constructor_msgs::action::ExecuteTaskSolution>(
235233
node_, "execute_task_solution");
236234

0 commit comments

Comments
 (0)