Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
gazebo::GazeboRosVacuumGripper Class Reference

#include <gazebo_ros_vacuum_gripper.h>

List of all members.

Public Member Functions

 GazeboRosVacuumGripper ()
 Constructor.
virtual ~GazeboRosVacuumGripper ()
 Destructor.

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.

Private Attributes

boost::thread callback_queue_thread_
 Thead object for the running callback Thread.
int connect_count_
 : keep track of number of connections
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.
boost::mutex lock_
 A mutex to lock access to fields that are used in ROS message callbacks.
physics::ModelPtr parent_
ros::Publisher pub_
ros::CallbackQueue queue_
std::string robot_namespace_
 for setting ROS name space
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist.
std::string service_name_
ros::ServiceServer srv1_
ros::ServiceServer srv2_
bool status_
std::string topic_name_
 ROS Wrench topic name inputs.
event::ConnectionPtr update_connection_
physics::WorldPtr world_
 A pointer to the gazebo world.

Detailed Description

Definition at line 95 of file gazebo_ros_vacuum_gripper.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 37 of file gazebo_ros_vacuum_gripper.cpp.

Destructor.

Definition at line 45 of file gazebo_ros_vacuum_gripper.cpp.


Member Function Documentation

Definition at line 235 of file gazebo_ros_vacuum_gripper.cpp.

Definition at line 242 of file gazebo_ros_vacuum_gripper.cpp.

void gazebo::GazeboRosVacuumGripper::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
) [protected]

Definition at line 60 of file gazebo_ros_vacuum_gripper.cpp.

bool gazebo::GazeboRosVacuumGripper::OffServiceCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [private]

Definition at line 158 of file gazebo_ros_vacuum_gripper.cpp.

bool gazebo::GazeboRosVacuumGripper::OnServiceCallback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [private]

Definition at line 147 of file gazebo_ros_vacuum_gripper.cpp.

The custom callback queue thread function.

Definition at line 223 of file gazebo_ros_vacuum_gripper.cpp.

void gazebo::GazeboRosVacuumGripper::UpdateChild ( ) [protected, virtual]

Definition at line 172 of file gazebo_ros_vacuum_gripper.cpp.


Member Data Documentation

Thead object for the running callback Thread.

Definition at line 148 of file gazebo_ros_vacuum_gripper.h.

: keep track of number of connections

Definition at line 154 of file gazebo_ros_vacuum_gripper.h.

physics::LinkPtr gazebo::GazeboRosVacuumGripper::link_ [private]

A pointer to the Link, where force is applied.

Definition at line 125 of file gazebo_ros_vacuum_gripper.h.

The Link this plugin is attached to, and will exert forces on.

Definition at line 140 of file gazebo_ros_vacuum_gripper.h.

boost::mutex gazebo::GazeboRosVacuumGripper::lock_ [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.

physics::ModelPtr gazebo::GazeboRosVacuumGripper::parent_ [private]

Definition at line 119 of file gazebo_ros_vacuum_gripper.h.

Definition at line 132 of file gazebo_ros_vacuum_gripper.h.

Definition at line 146 of file gazebo_ros_vacuum_gripper.h.

for setting ROS name space

Definition at line 143 of file gazebo_ros_vacuum_gripper.h.

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.

Definition at line 138 of file gazebo_ros_vacuum_gripper.h.

Definition at line 133 of file gazebo_ros_vacuum_gripper.h.

Definition at line 134 of file gazebo_ros_vacuum_gripper.h.

Definition at line 117 of file gazebo_ros_vacuum_gripper.h.

ROS Wrench topic name inputs.

Definition at line 137 of file gazebo_ros_vacuum_gripper.h.

Definition at line 151 of file gazebo_ros_vacuum_gripper.h.

physics::WorldPtr gazebo::GazeboRosVacuumGripper::world_ [private]

A pointer to the gazebo world.

Definition at line 122 of file gazebo_ros_vacuum_gripper.h.


The documentation for this class was generated from the following files:


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Feb 23 2017 03:43:23