basic_profiler_example_node.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <swri_profiler/profiler.h>
00003 #include <std_msgs/Int32.h>
00004 
00005 class BasicProfilerExampleNode
00006 {
00007   ros::NodeHandle nh_;
00008   ros::NodeHandle pnh_;
00009   
00010   ros::WallTimer init_timer_;
00011   ros::Timer update_timer_;
00012 
00013   ros::Subscriber int_callback_;
00014 
00015   int fibonacci_index1_;
00016   int fibonacci_index2_;
00017   
00018  public:
00019   BasicProfilerExampleNode()
00020   {
00021     pnh_ = ros::NodeHandle("~");
00022     
00023     // Setup a one-shot timer to initialize the node after a brief
00024     // delay so that /rosout is always fully initialized.
00025     ROS_INFO("Starting initialization timer...");
00026     init_timer_ = nh_.createWallTimer(ros::WallDuration(1.0),
00027                                       &BasicProfilerExampleNode::initialize,
00028                                       this,                                      
00029                                       true);    
00030   }
00031 
00032   void initialize(const ros::WallTimerEvent &ignored)
00033   {
00034     (void)ignored;
00035 
00036     pnh_.param("fibonacci_index1", fibonacci_index1_, 30);
00037     pnh_.param("fibonacci_index2", fibonacci_index2_, 40);
00038 
00039     update_timer_ = nh_.createTimer(ros::Duration(1/10.0),
00040                                     &BasicProfilerExampleNode::handleUpdateTimer,
00041                                     this);
00042 
00043     int_callback_ = nh_.subscribe("trigger_fibonacci", 10,
00044                                   &BasicProfilerExampleNode::handleTriggerFibonacci,
00045                                   this);
00046   }
00047   
00048   int superSlowFibonacciInt(int x)
00049   {
00050     if (x <= 0) {
00051       return 0;
00052     } else if (x == 1) {
00053       return 1;
00054     } else {
00055       return superSlowFibonacciInt(x-1) + superSlowFibonacciInt(x-2);
00056     }
00057   }
00058 
00059   int superSlowFibonacci(int x)
00060   {
00061     SWRI_PROFILE("super-slow-fibonacci");
00062     ROS_INFO("Fibonacci %d = %d", x, superSlowFibonacciInt(x));
00063   }
00064 
00065   void handleUpdateTimer(const ros::TimerEvent &ignored)
00066   {
00067     (void)ignored;
00068     SWRI_PROFILE("handle-update-timer");
00069 
00070     {
00071       SWRI_PROFILE("fibonacci-1");
00072       superSlowFibonacci(fibonacci_index1_);
00073     }
00074 
00075     {
00076       SWRI_PROFILE("fibonacci-2");
00077       superSlowFibonacci(fibonacci_index2_);
00078     }
00079   }
00080 
00081   void handleTriggerFibonacci(const std_msgs::Int32ConstPtr &msg)
00082   {
00083     SWRI_PROFILE("handle-trigger-fibonacci");
00084     superSlowFibonacci(msg->data);
00085   }
00086 };
00087 
00088 int main(int argc, char **argv)
00089 {
00090   ros::init(argc, argv, "basic_profiler_example");
00091 
00092   BasicProfilerExampleNode node;
00093   ros::spin();
00094   
00095   return 0;  
00096 }
00097 


swri_profiler
Author(s):
autogenerated on Sat Apr 27 2019 03:08:47