#include <gazebo_ros_vacuum_gripper.h>
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::NodeHandle * | rosnode_ |
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. |
Definition at line 95 of file gazebo_ros_vacuum_gripper.h.
Constructor.
Definition at line 37 of file gazebo_ros_vacuum_gripper.cpp.
gazebo::GazeboRosVacuumGripper::~GazeboRosVacuumGripper | ( | ) | [virtual] |
Destructor.
Definition at line 45 of file gazebo_ros_vacuum_gripper.cpp.
void gazebo::GazeboRosVacuumGripper::Connect | ( | ) | [private] |
Definition at line 235 of file gazebo_ros_vacuum_gripper.cpp.
void gazebo::GazeboRosVacuumGripper::Disconnect | ( | ) | [private] |
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.
void gazebo::GazeboRosVacuumGripper::QueueThread | ( | ) | [private] |
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.
boost::thread gazebo::GazeboRosVacuumGripper::callback_queue_thread_ [private] |
Thead object for the running callback Thread.
Definition at line 148 of file gazebo_ros_vacuum_gripper.h.
int gazebo::GazeboRosVacuumGripper::connect_count_ [private] |
: 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.
std::string gazebo::GazeboRosVacuumGripper::link_name_ [private] |
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.
std::string gazebo::GazeboRosVacuumGripper::robot_namespace_ [private] |
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.
std::string gazebo::GazeboRosVacuumGripper::service_name_ [private] |
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.
bool gazebo::GazeboRosVacuumGripper::status_ [private] |
Definition at line 117 of file gazebo_ros_vacuum_gripper.h.
std::string gazebo::GazeboRosVacuumGripper::topic_name_ [private] |
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.