#include <gazebo_ros_vacuum_gripper.h>

| Public Member Functions | |
| GazeboRosVacuumGripper () | |
| Constructor.  More... | |
| virtual | ~GazeboRosVacuumGripper () | 
| Destructor.  More... | |
| Protected Member Functions | |
| void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) | 
| virtual void | UpdateChild () | 
| Private Member Functions | |
| void | Connect () | 
| void | Disconnect () | 
| bool | OffServiceCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) | 
| bool | OnServiceCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) | 
| void | QueueThread () | 
| The custom callback queue thread function.  More... | |
| Private Attributes | |
| boost::thread | callback_queue_thread_ | 
| Thead object for the running callback Thread.  More... | |
| int | connect_count_ | 
| : keep track of number of connections  More... | |
| physics::LinkPtr | link_ | 
| A pointer to the Link, where force is applied.  More... | |
| std::string | link_name_ | 
| The Link this plugin is attached to, and will exert forces on.  More... | |
| boost::mutex | lock_ | 
| A mutex to lock access to fields that are used in ROS message callbacks.  More... | |
| physics::ModelPtr | parent_ | 
| ros::Publisher | pub_ | 
| ros::CallbackQueue | queue_ | 
| std::string | robot_namespace_ | 
| for setting ROS name space  More... | |
| ros::NodeHandle * | rosnode_ | 
| A pointer to the ROS node. A node will be instantiated if it does not exist.  More... | |
| std::string | service_name_ | 
| ros::ServiceServer | srv1_ | 
| ros::ServiceServer | srv2_ | 
| bool | status_ | 
| std::string | topic_name_ | 
| ROS Wrench topic name inputs.  More... | |
| event::ConnectionPtr | update_connection_ | 
| physics::WorldPtr | world_ | 
| A pointer to the gazebo world.  More... | |
Definition at line 95 of file gazebo_ros_vacuum_gripper.h.
| gazebo::GazeboRosVacuumGripper::GazeboRosVacuumGripper | ( | ) | 
Constructor.
Definition at line 39 of file gazebo_ros_vacuum_gripper.cpp.
| 
 | virtual | 
Destructor.
Definition at line 47 of file gazebo_ros_vacuum_gripper.cpp.
| 
 | private | 
Definition at line 268 of file gazebo_ros_vacuum_gripper.cpp.
| 
 | private | 
Definition at line 275 of file gazebo_ros_vacuum_gripper.cpp.
| 
 | protected | 
Definition at line 62 of file gazebo_ros_vacuum_gripper.cpp.
| 
 | private | 
Definition at line 160 of file gazebo_ros_vacuum_gripper.cpp.
| 
 | private | 
Definition at line 149 of file gazebo_ros_vacuum_gripper.cpp.
| 
 | private | 
The custom callback queue thread function.
Definition at line 256 of file gazebo_ros_vacuum_gripper.cpp.
| 
 | protectedvirtual | 
Definition at line 174 of file gazebo_ros_vacuum_gripper.cpp.
| 
 | private | 
Thead object for the running callback Thread.
Definition at line 148 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
: keep track of number of connections
Definition at line 154 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
A pointer to the Link, where force is applied.
Definition at line 125 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
The Link this plugin is attached to, and will exert forces on.
Definition at line 140 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
A mutex to lock access to fields that are used in ROS message callbacks.
Definition at line 131 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
Definition at line 119 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
Definition at line 132 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
Definition at line 146 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
for setting ROS name space
Definition at line 143 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition at line 128 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
Definition at line 138 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
Definition at line 133 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
Definition at line 134 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
Definition at line 117 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
ROS Wrench topic name inputs.
Definition at line 137 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
Definition at line 151 of file gazebo_ros_vacuum_gripper.h.
| 
 | private | 
A pointer to the gazebo world.
Definition at line 122 of file gazebo_ros_vacuum_gripper.h.