#include <robotiq_s_model_articulated_msgs/SModelRobotInput.h>#include <robotiq_s_model_articulated_msgs/SModelRobotOutput.h>#include <gazebo_plugins/PubQueue.h>#include <ros/advertise_options.h>#include <ros/callback_queue.h>#include <ros/ros.h>#include <ros/subscribe_options.h>#include <sensor_msgs/JointState.h>#include <string>#include <vector>#include <boost/scoped_ptr.hpp>#include <boost/thread/mutex.hpp>#include <gazebo/common/Plugin.hh>#include <gazebo/common/Time.hh>#include <gazebo/physics/physics.hh>

Go to the source code of this file.
Classes | |
| class | RobotiqHandPlugin |
| A plugin that implements the Robotiq 3-Finger Adaptative Gripper. The plugin exposes the next parameters via SDF tags: <side> Determines if we are controlling the left or right hand. This is a required parameter and the allowed values are 'left' or 'right' <kp_position> P gain for the PID that controls the position of the joints. This parameter is optional. <ki_position> I gain for the PID that controls the position of the joints. This parameter is optional. <kd_position> D gain for the PID that controls the position of the joints. This parameter is optional. <position_effort_min> Minimum output of the PID that controls the position of the joints. This parameter is optional <position_effort_max> Maximum output of the PID that controls the position of the joints. This parameter is optional <topic_command> ROS topic name used to send new commands to the hand. This parameter is optional. <topic_state> ROS topic name used to receive state from the hand. This parameter is optional. More... | |