gazebo_ros_ft_sensor.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: Force Torque Sensor Plugin
00019  * Author: Francisco Suarez-Ruiz
00020  * Date: 5 June 2014
00021  */
00022 
00023 #ifndef GAZEBO_ROS_FT_HH
00024 #define GAZEBO_ROS_FT_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 {
00044 
00072 
00073 
00074 class GazeboRosFT : public ModelPlugin
00075 {
00078   public: GazeboRosFT();
00079 
00081   public: virtual ~GazeboRosFT();
00082 
00084   public: void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
00085 
00087   protected: virtual void UpdateChild();
00088   
00090   private: double gaussian_noise_;
00091   private: unsigned int seed;
00093   private: double GaussianKernel(double mu, double sigma);
00094 
00096   private: physics::JointPtr joint_;
00097   
00099   private: physics::LinkPtr parent_link_;
00100   
00102   private: physics::LinkPtr child_link_;
00103   
00105   private: physics::ModelPtr model_;
00106   
00108   private: physics::WorldPtr world_;
00109 
00111   private: ros::NodeHandle* rosnode_;
00112   private: ros::Publisher pub_;
00113 
00115   private: geometry_msgs::WrenchStamped wrench_msg_;
00116 
00118   private: std::string joint_name_;
00119 
00121   private: std::string topic_name_;
00122 
00125   private: std::string frame_name_;
00126 
00128   private: std::string robot_namespace_;
00129 
00131   private: boost::mutex lock_;
00132   
00134   private: common::Time last_time_;
00135   
00136   // rate control
00137   private: double update_rate_;
00138 
00140   private: int ft_connect_count_;
00141   private: void FTConnect();
00142   private: void FTDisconnect();
00143 
00144   // Custom Callback Queue
00145   private: ros::CallbackQueue queue_;
00146   private: void QueueThread();
00147   private: boost::thread callback_queue_thread_;
00148 
00149   // Pointer to the update event connection
00150   private: event::ConnectionPtr update_connection_;
00151 
00152 };
00153 
00155 
00156 
00157 
00158 }
00159 
00160 #endif


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Jun 6 2019 18:41:09