9 #include <mrs_msgs/ProfilerUpdate.h>
18 Routine(std::string name, std::string node_name, std::shared_ptr<ros::Publisher> publisher, std::shared_ptr<std::mutex> mutex_publisher,
19 bool profiler_enabled);
20 Routine(std::string name, std::string node_name,
double expected_rate,
double threshold, std::shared_ptr<ros::Publisher> publisher,
21 std::shared_ptr<std::mutex> mutex_publisher,
bool profiler_enabled, ros::TimerEvent event);
27 std::string _routine_name_;
28 std::string _node_name_;
30 std::shared_ptr<ros::Publisher> publisher_;
31 std::shared_ptr<std::mutex> mutex_publisher_;
37 bool _profiler_enabled_ =
false;
40 ros::Time execution_start_;
43 mrs_msgs::ProfilerUpdate msg_out_;
61 Profiler(ros::NodeHandle& nh, std::string node_name,
bool profiler_enabled);
89 Routine createRoutine(std::string name,
double expected_rate,
double threshold, ros::TimerEvent event);
101 std::shared_ptr<ros::Publisher> publisher_;
102 std::shared_ptr<std::mutex> mutex_publisher_;
103 std::string _node_name_;
104 bool _profiler_enabled_ =
false;
106 std::shared_ptr<ros::NodeHandle> nh_;
108 bool is_initialized_ =
false;