Skip to content

Commit 3e526af

Browse files
authored
Initialize the namespace property for custom iMarkers in rviz (#3547)
1 parent 7d6e2ab commit 3e526af

File tree

1 file changed

+7
-7
lines changed

1 file changed

+7
-7
lines changed

moveit_ros/visualization/motion_planning_rviz_plugin/src/interactive_marker_display.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -91,13 +91,13 @@ InteractiveMarkerDisplay::InteractiveMarkerDisplay()
9191

9292
void InteractiveMarkerDisplay::onInitialize()
9393
{
94-
// auto ros_node_abstraction = context_->getRosNodeAbstraction().lock();
95-
// if (!ros_node_abstraction) {
96-
// return;
97-
// }
98-
//
99-
// interactive_marker_namespace_property_->initialize(ros_node_abstraction);
100-
//
94+
auto ros_node_abstraction = context_->getRosNodeAbstraction().lock();
95+
if (!ros_node_abstraction)
96+
{
97+
return;
98+
}
99+
interactive_marker_namespace_property_->initialize(ros_node_abstraction);
100+
101101
rclcpp::NodeOptions options;
102102
options.arguments({ "--ros-args", "-r",
103103
"__node:=" + std::string("interactive_marker_display_") +

0 commit comments

Comments
 (0)