gazebo_ros_ft_sensor.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2014 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 /*
18  * Desc: Force Torque Sensor Plugin
19  * Author: Francisco Suarez-Ruiz
20  * Date: 5 June 2014
21  */
22 
23 #ifndef GAZEBO_ROS_FT_HH
24 #define GAZEBO_ROS_FT_HH
25 
26 // Custom Callback Queue
27 #include <ros/callback_queue.h>
28 #include <ros/advertise_options.h>
29 
30 #include <gazebo/physics/physics.hh>
31 #include <gazebo/transport/TransportTypes.hh>
32 #include <gazebo/common/Plugin.hh>
33 #include <gazebo/common/Events.hh>
34 
35 #include <ros/ros.h>
36 #include <boost/thread.hpp>
37 #include <boost/thread/mutex.hpp>
38 #include <geometry_msgs/WrenchStamped.h>
39 
40 namespace gazebo
41 {
44 
72 class GazeboRosFT : public ModelPlugin
75 {
78  public: GazeboRosFT();
79 
81  public: virtual ~GazeboRosFT();
82 
84  public: void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
85 
87  protected: virtual void UpdateChild();
88 
90  private: double gaussian_noise_;
91 
93  private: double GaussianKernel(double mu, double sigma);
94 
96  private: physics::JointPtr joint_;
97 
99  private: physics::LinkPtr parent_link_;
100 
102  private: physics::LinkPtr child_link_;
103 
105  private: physics::ModelPtr model_;
106 
108  private: physics::WorldPtr world_;
109 
113 
115  private: geometry_msgs::WrenchStamped wrench_msg_;
116 
118  private: std::string joint_name_;
119 
121  private: std::string topic_name_;
122 
125  private: std::string frame_name_;
126 
128  private: std::string robot_namespace_;
129 
131  private: boost::mutex lock_;
132 
134  private: common::Time last_time_;
135 
136  // rate control
137  private: double update_rate_;
138 
140  private: int ft_connect_count_;
141  private: void FTConnect();
142  private: void FTDisconnect();
143 
144  // Custom Callback Queue
146  private: void QueueThread();
147  private: boost::thread callback_queue_thread_;
148 
149  // Pointer to the update event connection
150  private: event::ConnectionPtr update_connection_;
151 
152 };
153 
155 
157 
158 }
159 
160 #endif
virtual void UpdateChild()
Update the controller.
std::string topic_name_
ROS WrenchStamped topic name.
virtual ~GazeboRosFT()
Destructor.
int ft_connect_count_
: keep track of number of connections
std::string robot_namespace_
for setting ROS name space
physics::JointPtr joint_
A pointer to the Gazebo joint.
geometry_msgs::WrenchStamped wrench_msg_
ROS WrenchStamped message.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
ros::CallbackQueue queue_
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
boost::thread callback_queue_thread_
double gaussian_noise_
Gaussian noise.
physics::WorldPtr world_
A pointer to the Gazebo world.
event::ConnectionPtr update_connection_
physics::ModelPtr model_
A pointer to the Gazebo model.
physics::LinkPtr parent_link_
A pointer to the Gazebo parent link.
physics::LinkPtr child_link_
A pointer to the Gazebo child link.
common::Time last_time_
save last_time
std::string joint_name_
store bodyname
std::string frame_name_
ROS frame transform name to use in the image message header. FIXME: extract link name directly...


gazebo_plugins
Author(s): John Hsu
autogenerated on Wed Aug 24 2022 02:47:52