Go to the documentation of this file.
23 #ifndef GAZEBO_ROS_VACUUM_GRIPPER_HH
24 #define GAZEBO_ROS_VACUUM_GRIPPER_HH
32 #include <std_srvs/Empty.h>
35 #include <boost/thread.hpp>
36 #include <boost/thread/mutex.hpp>
38 #include <gazebo/physics/physics.hh>
39 #include <gazebo/transport/TransportTypes.hh>
40 #include <gazebo/common/Plugin.hh>
41 #include <gazebo/common/Events.hh>
104 protected:
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
113 std_srvs::Empty::Response &res);
115 std_srvs::Empty::Response &res);
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
void QueueThread()
The custom callback queue thread function.
std::string robot_namespace_
for setting ROS name space
physics::ModelPtr parent_
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
virtual ~GazeboRosVacuumGripper()
Destructor.
bool OnServiceCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
boost::thread callback_queue_thread_
Thead object for the running callback Thread.
bool OffServiceCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
physics::WorldPtr world_
A pointer to the gazebo world.
physics::LinkPtr link_
A pointer to the Link, where force is applied.
virtual void UpdateChild()
std::string link_name_
The Link this plugin is attached to, and will exert forces on.
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
int connect_count_
: keep track of number of connections
ros::CallbackQueue queue_
event::ConnectionPtr update_connection_
std::string service_name_
std::string topic_name_
ROS Wrench topic name inputs.
GazeboRosVacuumGripper()
Constructor.
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55