gazebo_ros_f3d.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: 3D Applied Force Feedback Interface
00019  * Author: John Hsu
00020  * Date: 24 Sept 2008
00021  */
00022 
00023 #ifndef GAZEBO_ROS_F3D_HH
00024 #define GAZEBO_ROS_F3D_HH
00025 
00026 // Custom Callback Queue
00027 #include <ros/callback_queue.h>
00028 #include <ros/advertise_options.h>
00029 
00030 #include <gazebo/physics/physics.hh>
00031 #include <gazebo/transport/TransportTypes.hh>
00032 #include <gazebo/common/Plugin.hh>
00033 #include <gazebo/common/Events.hh>
00034 
00035 #include <ros/ros.h>
00036 #include <boost/thread.hpp>
00037 #include <boost/thread/mutex.hpp>
00038 #include <geometry_msgs/WrenchStamped.h>
00039 
00040 namespace gazebo
00041 {
00042 
00045 class GazeboRosF3D : public ModelPlugin
00046 {
00049   public: GazeboRosF3D();
00050 
00052   public: virtual ~GazeboRosF3D();
00053 
00055   public: void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
00056 
00058   protected: virtual void UpdateChild();
00059   
00060   private: physics::WorldPtr world_;
00061 
00063   private: physics::LinkPtr link_;
00064 
00065 
00067   private: ros::NodeHandle* rosnode_;
00068   private: ros::Publisher pub_;
00069 
00071   private: geometry_msgs::WrenchStamped wrench_msg_;
00072 
00074   private: std::string link_name_;
00075 
00077   private: std::string topic_name_;
00078 
00081   private: std::string frame_name_;
00082 
00084   private: std::string robot_namespace_;
00085 
00087   private: boost::mutex lock_;
00088 
00090   private: int f3d_connect_count_;
00091   private: void F3DConnect();
00092   private: void F3DDisconnect();
00093 
00094   // Custom Callback Queue
00095   private: ros::CallbackQueue queue_;
00096   private: void QueueThread();
00097   private: boost::thread callback_queue_thread_;
00098 
00099   // Pointer to the update event connection
00100   private: event::ConnectionPtr update_connection_;
00101 
00102 };
00103 
00105 
00106 
00107 
00108 }
00109 
00110 #endif
00111 


gazebo_plugins
Author(s): John Hsu
autogenerated on Fri Aug 28 2015 10:47:25