00001 /* 00002 * Gazebo - Outdoor Multi-Robot Simulator 00003 * Copyright (C) 2003 00004 * Nate Koenig & Andrew Howard 00005 * 00006 * This program is free software; you can redistribute it and/or modify 00007 * it under the terms of the GNU General Public License as published by 00008 * the Free Software Foundation; either version 2 of the License, or 00009 * (at your option) any later version. 00010 * 00011 * This program is distributed in the hope that it will be useful, 00012 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 * GNU General Public License for more details. 00015 * 00016 * You should have received a copy of the GNU General Public License 00017 * along with this program; if not, write to the Free Software 00018 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00019 * 00020 */ 00021 /* 00022 * Desc: Plugin for testing pr2 simulator performance 00023 * Author: John Hsu 00024 * Date: 1 July 2010 00025 * SVN: $Id$ 00026 */ 00027 #ifndef GAZEBO_ROS_BENCHMARKS_HH 00028 #define GAZEBO_ROS_BENCHMARKS_HH 00029 00030 #include <ros/ros.h> 00031 #include <ros/callback_queue.h> 00032 00033 #include <gazebo/gazeboserver.hh> 00034 #include <pr2_gazebo_benchmarks/GazeboBenchmarks.h> 00035 #include "std_srvs/Empty.h" 00036 00037 #include "boost/thread/mutex.hpp" 00038 00039 namespace gazebo 00040 { 00041 00042 class GazeboRosBenchmarks : public Plugin 00043 { 00046 public: GazeboRosBenchmarks(); 00047 00049 public: ~GazeboRosBenchmarks(); 00050 00053 protected: void Load(); 00054 00056 protected: void UpdateCBWorldUpdateStart(); 00057 protected: void UpdateCBWorldUpdateEnd(); 00058 00060 private: boost::mutex lock; 00061 00063 private: ros::NodeHandle* rosnode_; 00065 private: ros::CallbackQueue ros_queue_; 00066 private: void RosQueueThread(); 00067 private: boost::thread* ros_callback_queue_thread_; 00068 00070 private: bool timing_initialized_; 00071 private: gazebo::Time world_update_start_sim_time_; 00072 private: gazebo::Time world_update_start_wall_time_; 00073 private: gazebo::Time world_update_end_sim_time_; 00074 private: gazebo::Time world_update_end_wall_time_; 00075 00076 private: gazebo::Time last_world_update_start_sim_time_; 00077 private: gazebo::Time last_world_update_start_wall_time_; 00078 private: gazebo::Time last_world_update_end_sim_time_; 00079 private: gazebo::Time last_world_update_end_wall_time_; 00080 00082 private: pr2_gazebo_benchmarks::GazeboBenchmarks world_update_pr2_gazebo_benchmarks_; 00083 private: ros::Publisher world_update_pub_; 00085 private: int world_update_ros_connect_count_; 00086 private: void WorldUpdateRosConnect() {this->world_update_ros_connect_count_++;}; 00087 private: void WorldUpdateRosDisconnect() {this->world_update_ros_connect_count_--;}; 00088 00090 private: pr2_gazebo_benchmarks::GazeboBenchmarks simulation_cycle_pr2_gazebo_benchmarks_; 00091 private: ros::Publisher simulation_cycle_pub_; 00093 private: int simulation_cycle_ros_connect_count_; 00094 private: void SimulationCycleRosConnect() {this->simulation_cycle_ros_connect_count_++;}; 00095 private: void SimulationCycleRosDisconnect() {this->simulation_cycle_ros_connect_count_--;}; 00096 00097 00099 private: ros::ServiceServer reset_timing_service_; 00100 private: bool ResetTimingStatistics(std_srvs::Empty::Request &req,std_srvs::Empty::Response &res); 00101 00102 00103 }; 00104 00106 00107 00108 } 00109 #endif 00110