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_SIM_IFACE_HH
00028 #define GAZEBO_ROS_SIM_IFACE_HH
00029
00030
00031 #include <ros/callback_queue.h>
00032 #include <ros/subscribe_options.h>
00033
00034 #include <ros/ros.h>
00035 #include "boost/thread/mutex.hpp"
00036 #include <gazebo/Controller.hh>
00037 #include <gazebo/Param.hh>
00038 #include <nav_msgs/Odometry.h>
00039
00040 #include <gazebo/Body.hh>
00041
00042 #define ROS_SIM_IFACE_EXPOSE_SERVICE 1
00043
00044 #if ROS_SIM_IFACE_EXPOSE_SERVICE
00045 #include <gazebo_plugins/SetPose.h>
00046 #endif
00047
00048
00049 namespace gazebo
00050 {
00051
00054
00083 class GazeboRosSimIface : public Controller
00084 {
00087 public: GazeboRosSimIface(Entity *parent);
00088
00090 public: virtual ~GazeboRosSimIface();
00091
00094 protected: virtual void LoadChild(XMLConfigNode *node);
00095
00097 protected: virtual void InitChild();
00098
00100 protected: virtual void UpdateChild();
00101
00103 protected: virtual void FiniChild();
00104
00106 private: void UpdateObjectPose(const nav_msgs::Odometry::ConstPtr& poseMsg);
00107
00109 private: bool ServiceCallback(gazebo_plugins::SetPose::Request &req,
00110 gazebo_plugins::SetPose::Response &res);
00111
00113 private: Entity *myParent;
00114
00116 private: ros::NodeHandle* rosnode_;
00117 private: ros::Subscriber sub_;
00118 private: ros::ServiceServer srv_;
00119
00121 private: boost::mutex lock;
00122
00127 private: ParamT<std::string> *topicNameP,*modelNameP;
00128 private: ParamT<Vector3> *xyzP,*rpyP,*velP,*angVelP;
00129 private: std::string topicName,frameName,modelName;
00130 private: Vector3 xyz,rpy,vel,angVel;
00131 private: ParamT<std::string> *serviceNameP;
00132 private: std::string serviceName;
00133
00135 private: ParamT<std::string> *robotNamespaceP;
00136 private: std::string robotNamespace;
00137
00138
00139 private: ros::CallbackQueue queue_;
00140 private: void QueueThread();
00141 private: boost::thread callback_queue_thread_;
00142 private: Body* myFrame;
00143
00144 };
00145
00147
00148
00149 }
00150 #endif
00151