gazebo_ros_force.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2012-2014 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 /*
00018  * Desc: A dynamic controller plugin that performs generic force interface.
00019  * Author: John Hsu
00020  * Date: 24 Sept 2008
00021  */
00022 
00023 #ifndef GAZEBO_ROS_FORCE_HH
00024 #define GAZEBO_ROS_FORCE_HH
00025 
00026 #include <string>
00027 
00028 // Custom Callback Queue
00029 #include <ros/callback_queue.h>
00030 #include <ros/subscribe_options.h>
00031 #include <geometry_msgs/Wrench.h>
00032 
00033 #include <ros/ros.h>
00034 #include <boost/thread.hpp>
00035 #include <boost/thread/mutex.hpp>
00036 
00037 #include <gazebo/physics/physics.hh>
00038 #include <gazebo/transport/TransportTypes.hh>
00039 #include <gazebo/common/Plugin.hh>
00040 #include <gazebo/common/Events.hh>
00041 
00042 
00043 namespace gazebo
00044 {
00047 
00071 class GazeboRosForce : public ModelPlugin
00072 {
00074   public: GazeboRosForce();
00075 
00077   public: virtual ~GazeboRosForce();
00078 
00079   // Documentation inherited
00080   protected: void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
00081 
00082   // Documentation inherited
00083   protected: virtual void UpdateChild();
00084 
00087   private: void UpdateObjectForce(const geometry_msgs::Wrench::ConstPtr& _msg);
00088 
00090   private: void QueueThread();
00091 
00093   private: physics::WorldPtr world_;
00094 
00096   private: physics::LinkPtr link_;
00097 
00099   private: ros::NodeHandle* rosnode_;
00100   private: ros::Subscriber sub_;
00101 
00103   private: boost::mutex lock_;
00104 
00106   private: std::string topic_name_;
00108   private: std::string link_name_;
00109 
00111   private: std::string robot_namespace_;
00112 
00113   // Custom Callback Queue
00114   private: ros::CallbackQueue queue_;
00116   private: boost::thread callback_queue_thread_;
00118   private: geometry_msgs::Wrench wrench_msg_;
00119 
00120   // Pointer to the update event connection
00121   private: event::ConnectionPtr update_connection_;
00122 };
00124 
00125 }
00126 #endif


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Feb 23 2017 03:43:22