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_FORCE_HH
00028 #define GAZEBO_ROS_FORCE_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 <gazebo/Body.hh>
00039 #include <gazebo/Model.hh>
00040 #include <geometry_msgs/Wrench.h>
00041
00042 namespace gazebo
00043 {
00044
00047
00076 class GazeboRosForce : public Controller
00077 {
00080 public: GazeboRosForce(Entity *parent);
00081
00083 public: virtual ~GazeboRosForce();
00084
00087 protected: virtual void LoadChild(XMLConfigNode *node);
00088
00090 protected: virtual void InitChild();
00091
00093 protected: virtual void UpdateChild();
00094
00096 protected: virtual void FiniChild();
00097
00099 private: void UpdateObjectForce(const geometry_msgs::Wrench::ConstPtr& wrenchMsg);
00100
00102 private: Model *myParent;
00103
00105 private: Body *myBody;
00106
00108 private: ros::NodeHandle* rosnode_;
00109 private: ros::Subscriber sub_;
00110
00112 private: boost::mutex lock;
00113
00116 private: ParamT<std::string> *topicNameP,*bodyNameP;
00117 private: std::string topicName,bodyName;
00118
00120 private: ParamT<std::string> *robotNamespaceP;
00121 private: std::string robotNamespace;
00122
00123
00124 private: ros::CallbackQueue queue_;
00125 private: void QueueThread();
00126 private: boost::thread callback_queue_thread_;
00127 private: geometry_msgs::Wrench wrench;
00128
00129 };
00130
00132
00133
00134 }
00135 #endif
00136