gazebo_ros_f3d.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: 3D Applied Force Feedback Interface
19  * Author: John Hsu
20  * Date: 24 Sept 2008
21  */
22 
23 #ifndef GAZEBO_ROS_F3D_HH
24 #define GAZEBO_ROS_F3D_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 {
42 
45 class GazeboRosF3D : public ModelPlugin
46 {
49  public: GazeboRosF3D();
50 
52  public: virtual ~GazeboRosF3D();
53 
55  public: void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
56 
58  protected: virtual void UpdateChild();
59 
60  private: physics::WorldPtr world_;
61 
63  private: physics::LinkPtr link_;
64 
65 
68  private: ros::Publisher pub_;
69 
71  private: geometry_msgs::WrenchStamped wrench_msg_;
72 
74  private: std::string link_name_;
75 
77  private: std::string topic_name_;
78 
81  private: std::string frame_name_;
82 
84  private: std::string robot_namespace_;
85 
87  private: boost::mutex lock_;
88 
90  private: int f3d_connect_count_;
91  private: void F3DConnect();
92  private: void F3DDisconnect();
93 
94  // Custom Callback Queue
96  private: void QueueThread();
97  private: boost::thread callback_queue_thread_;
98 
99  // Pointer to the update event connection
100  private: event::ConnectionPtr update_connection_;
101 
102 };
103 
105 
107 
108 }
109 
110 #endif
111 
boost::thread callback_queue_thread_
GazeboRosF3D controller This is a controller that simulates a 6 dof force sensor. ...
std::string topic_name_
ROS WrenchStamped topic name.
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
physics::LinkPtr link_
A pointer to the Gazebo Body.
int f3d_connect_count_
: keep track of number of connections
std::string frame_name_
ROS frame transform name to use in the image message header. This should be simply map since the retu...
GazeboRosF3D()
Constructor.
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
std::string link_name_
store bodyname
virtual void UpdateChild()
Update the controller.
event::ConnectionPtr update_connection_
ros::CallbackQueue queue_
std::string robot_namespace_
for setting ROS name space
boost::mutex lock_
A mutex to lock access to fields that are used in message callbacks.
ros::Publisher pub_
geometry_msgs::WrenchStamped wrench_msg_
ROS WrenchStamped message.
physics::WorldPtr world_
virtual ~GazeboRosF3D()
Destructor.


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