Skip to content

Commit a48149f

Browse files
Add display the list of nodes and the number of threads.
1 parent f60963f commit a48149f

File tree

2 files changed

+30
-0
lines changed

2 files changed

+30
-0
lines changed

include/dynamic_graph_bridge/ros.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,11 @@ typedef std_srvs::srv::Empty EmptyServiceType;
6767
*/
6868
RosNodePtr get_ros_node(std::string node_name);
6969

70+
71+
size_t ros_executor_get_nb_threads();
72+
73+
void ros_display_list_of_nodes();
74+
7075
/**
7176
* @brief Add a ros node to the global executor.
7277
*

src/ros.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -131,6 +131,13 @@ class Executor {
131131
}
132132
}
133133

134+
/**
135+
* @brief Return the number of threads
136+
*/
137+
size_t get_number_of_threads() {
138+
return ros_executor_.get_number_of_threads();
139+
}
140+
134141
private:
135142
/**
136143
* @brief Thread callback function
@@ -204,6 +211,7 @@ std::string executable_name() {
204211
#endif
205212
}
206213

214+
207215
/**
208216
* @brief Private function that allow us to initialize ROS only once.
209217
*/
@@ -273,6 +281,23 @@ void ros_shutdown() {
273281
// rclcpp::shutdown();
274282
}
275283

284+
size_t ros_executor_get_nb_threads() {
285+
return get_ros_executor()->get_number_of_threads();
286+
}
287+
288+
void ros_display_list_of_nodes() {
289+
GlobalListOfRosNodeType::iterator ros_node_it =
290+
GLOBAL_LIST_OF_ROS_NODE.begin();
291+
while(ros_node_it!=GLOBAL_LIST_OF_ROS_NODE.end()) {
292+
RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
293+
"ros_display_list_of_nodes: %s/%s",
294+
ros_node_it->second->get_namespace(),
295+
ros_node_it->second->get_name());
296+
ros_node_it++;
297+
}
298+
299+
}
300+
276301
void ros_clean() {
277302
ros_stop_spinning();
278303
GlobalListOfRosNodeType::iterator ros_node_it =

0 commit comments

Comments
 (0)