00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #ifndef GAZEBO_ROS_TIME_HH
00028 #define GAZEBO_ROS_TIME_HH
00029
00030 #include <gazebo/Controller.hh>
00031 #include <gazebo/Body.hh>
00032 #include <gazebo/World.hh>
00033 #include <gazebo/Param.hh>
00034
00035 #include <ros/ros.h>
00036 #include "boost/thread/mutex.hpp"
00037
00038
00039 #include <roslib/Clock.h>
00040
00041 namespace gazebo
00042 {
00045
00101 class GazeboRosTime : public Controller
00102 {
00105 public: GazeboRosTime(Entity *parent);
00106
00108 public: virtual ~GazeboRosTime();
00109
00112 protected: virtual void LoadChild(XMLConfigNode *node);
00113
00115 protected: virtual void InitChild();
00116
00118 protected: virtual void UpdateChild();
00119
00121 protected: virtual void FiniChild();
00122
00124 private: boost::mutex lock;
00125
00127 private: ros::NodeHandle* rosnode_;
00128 private: ros::Publisher pub_;
00129
00130 roslib::Clock timeMsg;
00131
00133 private: ParamT<std::string> *robotNamespaceP;
00134 private: std::string robotNamespace;
00135
00136 };
00137
00139
00140
00141 }
00142 #endif
00143