gazebo_ros_vacuum_gripper.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015-2016 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: GazeboVacuumGripper plugin for manipulating objects in Gazebo
19  * Author: Kentaro Wada
20  * Date: 7 Dec 2015
21  */
22 
23 #ifndef GAZEBO_ROS_VACUUM_GRIPPER_HH
24 #define GAZEBO_ROS_VACUUM_GRIPPER_HH
25 
26 #include <string>
27 
28 // Custom Callback Queue
29 #include <ros/callback_queue.h>
30 #include <ros/advertise_options.h>
32 #include <std_srvs/Empty.h>
33 
34 #include <ros/ros.h>
35 #include <boost/thread.hpp>
36 #include <boost/thread/mutex.hpp>
37 
38 #include <gazebo/physics/physics.hh>
39 #include <gazebo/transport/TransportTypes.hh>
40 #include <gazebo/common/Plugin.hh>
41 #include <gazebo/common/Events.hh>
42 
43 
44 namespace gazebo
45 {
48 
95 class GazeboRosVacuumGripper : public ModelPlugin
96 {
98  public: GazeboRosVacuumGripper();
99 
101  public: virtual ~GazeboRosVacuumGripper();
102 
103  // Documentation inherited
104  protected: void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
105 
106  // Documentation inherited
107  protected: virtual void UpdateChild();
108 
110  private: void QueueThread();
111 
112  private: bool OnServiceCallback(std_srvs::Empty::Request &req,
113  std_srvs::Empty::Response &res);
114  private: bool OffServiceCallback(std_srvs::Empty::Request &req,
115  std_srvs::Empty::Response &res);
116 
117  private: bool status_;
118 
119  private: physics::ModelPtr parent_;
120 
122  private: physics::WorldPtr world_;
123 
125  private: physics::LinkPtr link_;
126 
129 
131  private: boost::mutex lock_;
135 
137  private: std::string topic_name_;
138  private: std::string service_name_;
140  private: std::string link_name_;
141 
143  private: std::string robot_namespace_;
144 
145  // Custom Callback Queue
148  private: boost::thread callback_queue_thread_;
149 
150  // Pointer to the update event connection
151  private: event::ConnectionPtr update_connection_;
152 
154  private: int connect_count_;
155  private: void Connect();
156  private: void Disconnect();
157 };
159 }
161 #endif
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
boost::thread callback_queue_thread_
Thead object for the running callback Thread.
std::string robot_namespace_
for setting ROS name space
void QueueThread()
The custom callback queue thread function.
physics::WorldPtr world_
A pointer to the gazebo world.
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
bool OnServiceCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
physics::LinkPtr link_
A pointer to the Link, where force is applied.
std::string link_name_
The Link this plugin is attached to, and will exert forces on.
int connect_count_
: keep track of number of connections
bool OffServiceCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
std::string topic_name_
ROS Wrench topic name inputs.
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Apr 6 2021 02:19:39