21 #include <robotiq_3f_gripper_articulated_msgs/Robotiq3FGripperRobotInput.h> 22 #include <robotiq_3f_gripper_articulated_msgs/Robotiq3FGripperRobotOutput.h> 34 #define private public 35 #include <gazebo/common/Plugin.hh> 36 #include <gazebo/common/Time.hh> 37 #include <gazebo/physics/physics.hh> 47 "/right_hand/command";
57 this->
posePID[i].Init(1.0, 0, 0.5, 0.0, 0.0, 60.0, -60.0);
71 #if GAZEBO_MAJOR_VERSION < 9 84 this->
model = _parent;
88 if (!this->
sdf->HasElement(
"side") ||
89 !this->
sdf->GetElement(
"side")->GetValue()->Get(this->
side) ||
90 ((this->
side !=
"left") && (this->
side !=
"right")))
92 gzerr <<
"Failed to determine which hand we're controlling; " 93 "aborting plugin load. <Side> should be either 'left' or 'right'." 100 if (this->
side ==
"left")
109 gzlog <<
"Prior to iterating.." << std::endl;
115 gzlog <<
"About to iterate things.." << std::endl;
116 for (
size_t i = 0; i < this->
jointNames.size(); ++i)
123 gzlog <<
"Initialized the joint state vector" << std::endl;
128 if (this->
side ==
"right")
133 gzlog <<
"Using control topic " << controlTopicName << std::endl;
135 for (
int i = 0; i < this->
NumJoints; ++i)
142 if (this->
sdf->HasElement(
"kp_position"))
143 this->
posePID[i].SetPGain(this->
sdf->Get<
double>(
"kp_position"));
145 if (this->
sdf->HasElement(
"ki_position"))
146 this->
posePID[i].SetIGain(this->
sdf->Get<
double>(
"ki_position"));
148 if (this->
sdf->HasElement(
"kd_position"))
150 this->
posePID[i].SetDGain(this->
sdf->Get<
double>(
"kd_position"));
151 std::cout <<
"dGain after overloading: " << this->
posePID[i].dGain
155 if (this->
sdf->HasElement(
"position_effort_min"))
156 this->
posePID[i].SetCmdMin(this->
sdf->Get<
double>(
"position_effort_min"));
158 if (this->
sdf->HasElement(
"position_effort_max"))
159 this->
posePID[i].SetCmdMax(this->
sdf->Get<
double>(
"position_effort_max"));
163 if (this->
sdf->HasElement(
"topic_command"))
164 controlTopicName = this->
sdf->Get<std::string>(
"topic_command");
166 if (this->
sdf->HasElement(
"topic_state"))
167 stateTopicName = this->
sdf->Get<std::string>(
"topic_state");
172 gzerr <<
"Not loading plugin since ROS hasn't been " 173 <<
"properly initialized. Try starting gazebo with ROS plugin:\n" 174 <<
" gazebo -s libgazebo_ros_api_plugin.so\n";
186 this->
pubHandleState = this->
rosNode->advertise<robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput>(
187 stateTopicName, 100,
true);
190 std::string topicBase = std::string(
"robotiq_hands/") + this->
side;
193 topicBase + std::string(
"_hand/joint_states"), 10);
197 ros::SubscribeOptions::create<robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput>(
198 controlTopicName, 100,
208 #if GAZEBO_MAJOR_VERSION >= 9 220 gazebo::event::Events::ConnectWorldUpdateBegin(
224 gzlog <<
"RobotiqHandPlugin loaded for " << this->
side <<
" hand." 226 for (
int i = 0; i < this->
NumJoints; ++i)
228 gzlog <<
"Position PID parameters for joint [" 229 << this->
fingerJoints[i]->GetName() <<
"]:" << std::endl
230 <<
"\tKP: " << this->
posePID[i].pGain << std::endl
231 <<
"\tKI: " << this->
posePID[i].iGain << std::endl
232 <<
"\tKD: " << this->
posePID[i].dGain << std::endl
233 <<
"\tIMin: " << this->
posePID[i].iMin << std::endl
234 <<
"\tIMax: " << this->
posePID[i].iMax << std::endl
235 <<
"\tCmdMin: " << this->
posePID[i].cmdMin << std::endl
236 <<
"\tCmdMax: " << this->
posePID[i].cmdMax << std::endl
239 gzlog <<
"Topic for sending hand commands: [" << controlTopicName
240 <<
"]\nTopic for receiving hand state: [" << stateTopicName
248 if (_v < _min || _v > _max)
250 std::cerr <<
"Illegal " << _label <<
" value: [" << _v <<
"]. The correct " 251 <<
"range is [" << _min <<
"," << _max <<
"]" << std::endl;
259 const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &_command)
261 return this->
VerifyField(
"rACT", 0, 1, _command->rACT) &&
267 this->
VerifyField(
"rPRA", 0, 255, _command->rACT) &&
268 this->
VerifyField(
"rSPA", 0, 255, _command->rACT) &&
269 this->
VerifyField(
"rFRA", 0, 255, _command->rACT) &&
270 this->
VerifyField(
"rPRB", 0, 255, _command->rACT) &&
271 this->
VerifyField(
"rSPB", 0, 255, _command->rACT) &&
272 this->
VerifyField(
"rFRB", 0, 255, _command->rACT) &&
273 this->
VerifyField(
"rPRC", 0, 255, _command->rACT) &&
274 this->
VerifyField(
"rSPC", 0, 255, _command->rACT) &&
275 this->
VerifyField(
"rFRC", 0, 255, _command->rACT) &&
276 this->
VerifyField(
"rPRS", 0, 255, _command->rACT) &&
277 this->
VerifyField(
"rSPS", 0, 255, _command->rACT) &&
283 const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &_msg)
290 std::cerr <<
"Ignoring command" << std::endl;
326 bool fingersOpen =
true;
330 #if GAZEBO_MAJOR_VERSION >= 9 331 ignition::math::Angle tolerance;
332 tolerance.Degree(1.0);
334 gazebo::math::Angle tolerance;
335 tolerance.SetFromDegree(1.0);
338 for (
int i = 2; i < this->
NumJoints; ++i)
340 fingersOpen = fingersOpen &&
341 #if GAZEBO_MAJOR_VERSION >= 9 342 (this->
joints[i]->Position(0) < (this->
joints[i]->LowerLimit(0) + tolerance()));
344 (this->
joints[i]->GetAngle(0) < (this->
joints[i]->GetLowerLimit(0) + tolerance));
355 #if GAZEBO_MAJOR_VERSION >= 9 356 gazebo::common::Time curTime = this->
world->SimTime();
358 gazebo::common::Time curTime = this->
world->GetSimTime();
389 if (static_cast<int>(this->
handleCommand.rMOD) != this->graspingMode)
429 std::cerr <<
"Individual Control of Scissor not supported" << std::endl;
465 std::cerr <<
"Unrecognized state [" << this->
handState <<
"]" 484 const gazebo::physics::JointPtr &_joint,
int _index, uint8_t _rPR,
488 bool isMoving = _joint->GetVelocity(0) > this->
VelTolerance;
493 this->
posePID[_index].GetErrors(pe, ie, de);
508 else if (_rPR - _prevrPR > 0)
523 const gazebo::physics::JointPtr &_joint)
526 #if GAZEBO_MAJOR_VERSION >= 9 527 ignition::math::Angle range = _joint->UpperLimit(0) - _joint->LowerLimit(0);
529 gazebo::math::Angle range = _joint->GetUpperLimit(0) - _joint->GetLowerLimit(0);
534 range *= 177.0 / 255.0;
537 #if GAZEBO_MAJOR_VERSION >= 9 538 ignition::math::Angle relAngle = _joint->Position(0) - _joint->LowerLimit(0);
540 gazebo::math::Angle relAngle = _joint->GetAngle(0) - _joint->GetLowerLimit(0);
543 #if GAZEBO_MAJOR_VERSION >= 9 544 return static_cast<uint8_t
>(round(255.0 * relAngle() / range()));
546 static_cast<uint8_t
>(round(255.0 * relAngle.Radian() / range.Radian()));
577 this->
posePID[2].GetErrors(pe, ie, de);
579 this->
posePID[3].GetErrors(pe, ie, de);
581 this->
posePID[4].GetErrors(pe, ie, de);
585 if (isMovingA || isMovingB || isMovingC)
592 if (reachPositionA && reachPositionB && reachPositionC)
597 else if (!reachPositionA && !reachPositionB && !reachPositionC)
669 const gazebo::common::Time &_curTime)
672 for (
size_t i = 0; i < this->
joints.size(); ++i)
674 #if GAZEBO_MAJOR_VERSION >= 9 691 for (
int i = 0; i < this->
NumJoints; ++i)
697 for (
int i = 0; i < this->
NumJoints; ++i)
699 double targetPose = 0.0;
707 #if GAZEBO_MAJOR_VERSION >= 9 708 targetPose = this->
joints[i]->UpperLimit(0);
710 targetPose = this->
joints[i]->GetUpperLimit(0).Radian();
716 targetPose = -0.1919;
721 #if GAZEBO_MAJOR_VERSION >= 9 722 targetPose = this->
joints[i]->UpperLimit(0) -
723 (this->
joints[i]->UpperLimit(0) -
724 this->
joints[i]->LowerLimit(0)) * (215.0 / 255.0)
726 targetPose = this->
joints[i]->GetUpperLimit(0).Radian() -
727 (this->
joints[i]->GetUpperLimit(0).Radian() -
728 this->
joints[i]->GetLowerLimit(0).Radian()) * (215.0 / 255.0)
739 #if GAZEBO_MAJOR_VERSION >= 9 740 targetPose = this->
joints[i]->LowerLimit(0);
742 targetPose = this->
joints[i]->GetLowerLimit(0).Radian();
753 #if GAZEBO_MAJOR_VERSION >= 9 754 targetPose = this->
joints[i]->LowerLimit(0) +
755 (this->
joints[i]->UpperLimit(0) -
756 this->
joints[i]->LowerLimit(0)) * (215.0 / 255.0)
758 targetPose = this->
joints[i]->GetLowerLimit(0).Radian() +
759 (this->
joints[i]->GetUpperLimit(0).Radian() -
760 this->
joints[i]->GetLowerLimit(0).Radian()) * (215.0 / 255.0)
766 else if (i >= 2 && i <= 4)
771 #if GAZEBO_MAJOR_VERSION >= 9 772 targetPose = this->
joints[i]->LowerLimit(0) +
773 (this->
joints[i]->UpperLimit(0) -
774 this->
joints[i]->LowerLimit(0)) * (177.0 / 255.0)
776 targetPose = this->
joints[i]->GetLowerLimit(0).Radian() +
777 (this->
joints[i]->GetUpperLimit(0).Radian() -
778 this->
joints[i]->GetLowerLimit(0).Radian()) * (177.0 / 255.0)
790 #if GAZEBO_MAJOR_VERSION >= 9 791 targetPose = this->
joints[i]->LowerLimit(0) +
792 (this->
joints[i]->UpperLimit(0) -
793 this->
joints[i]->LowerLimit(0))
795 targetPose = this->
joints[i]->GetLowerLimit(0).Radian() +
796 (this->
joints[i]->GetUpperLimit(0).Radian() -
797 this->
joints[i]->GetLowerLimit(0).Radian())
804 #if GAZEBO_MAJOR_VERSION >= 9 805 double currentPose = this->
joints[i]->Position(0);
807 double currentPose = this->
joints[i]->GetAngle(0).Radian();
811 double poseError = currentPose - targetPose;
814 double torque = this->
posePID[i].Update(poseError, _dt);
823 gazebo::physics::Joint_V& _joints)
825 gazebo::physics::JointPtr joint = this->
model->GetJoint(_jointName);
829 gzerr <<
"Failed to find joint [" << _jointName
830 <<
"] aborting plugin load." << std::endl;
833 _joints.push_back(joint);
834 gzlog <<
"RobotiqHandPlugin found joint [" << _jointName <<
"]" << std::endl;
842 gazebo::physics::JointPtr joint;
845 if (this->
side ==
"left")
851 suffix =
"palm_finger_1_joint";
859 suffix =
"palm_finger_2_joint";
868 suffix =
"finger_1_joint_proximal_actuating_hinge";
871 suffix =
"finger_1_joint_1";
878 suffix =
"finger_2_joint_proximal_actuating_hinge";
881 suffix =
"finger_2_joint_1";
888 suffix =
"finger_middle_joint_proximal_actuating_hinge";
891 suffix =
"finger_middle_joint_1";
897 suffix =
"finger_1_joint_2";
903 suffix =
"finger_1_joint_3";
909 suffix =
"finger_2_joint_2";
915 suffix =
"finger_2_joint_3";
921 suffix =
"palm_finger_middle_joint";
927 suffix =
"finger_middle_joint_2";
933 suffix =
"finger_middle_joint_3";
938 gzlog <<
"RobotiqHandPlugin found all joints for " << this->
side 939 <<
" hand." << std::endl;
946 static const double timeout = 0.01;
GZ_REGISTER_MODEL_PLUGIN(GazeboRosElevator)
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput prevCommand
Previous command received. We know if the hand is opening or closing by comparing the current command...
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput handleState
Robotiq Hand State.
void push(T &msg, ros::Publisher &pub)
gazebo::common::Time lastControllerUpdateTime
keep track of controller update sim-time.
void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
static const int NumJoints
Number of joints in the hand. The three fingers can do abduction/adduction. Fingers 1 and 2 can do ci...
ros::Publisher pubHandleState
ROS publisher for Robotiq Hand state.
bool VerifyField(const std::string &_label, int _min, int _max, int _v)
Verify that one command field is within the correct range.
TransportHints & reliable()
void UpdatePIDControl(double _dt)
Update PID Joint controllers.
static constexpr double MinVelocity
Min. joint speed (rad/s). Finger is 125mm and tip speed is 22mm/s.
ROSCPP_DECL bool isInitialized()
sdf::ElementPtr sdf
Pointer to the SDF of this plugin.
std::string side
Used to select between 'left' or 'right' hand.
gazebo::event::ConnectionPtr updateConnection
gazebo world update connection.
void GetAndPublishHandleState()
Publish Robotiq Hand state.
gazebo::physics::Joint_V joints
Vector containing all the joints.
static constexpr double PoseTolerance
Position tolerance. If the difference between target position and current position is within this val...
static constexpr double MaxVelocity
Max. joint speed (rad/s). Finger is 125mm and tip speed is 110mm/s.
boost::mutex controlMutex
Controller update mutex.
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput userHandleCommand
Original HandleControl message (published by user and unmodified).
TransportHints & tcpNoDelay(bool nodelay=true)
std::vector< std::string > jointNames
Vector containing all the joint names.
gazebo::physics::WorldPtr world
World pointer.
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput lastHandleCommand
HandleControl message. Last command received before changing the grasping mode.
gazebo::physics::ModelPtr model
Parent model of the hand.
void SetHandleCommand(const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &_msg)
ROS topic callback to update Robotiq Hand Control Commands.
gazebo::physics::Joint_V fingerJoints
Vector containing all the actuated finger joints.
sensor_msgs::JointState jointStates
ROS joint state message.
static const std::string DefaultRightTopicCommand
Default topic name for sending control updates to the right hand.
GraspingMode
Different grasping modes.
bool FindJoints()
Grab pointers to all the joints.
PubQueue< robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotInput >::Ptr pubHandleStateQueue
ROS publisher queue for Robotiq Hand state.
static const std::string DefaultLeftTopicState
Default topic name for receiving state updates from the left hand.
GraspingMode graspingMode
Grasping mode.
uint8_t GetObjectDetection(const gazebo::physics::JointPtr &_joint, int _index, uint8_t _rPR, uint8_t _prevrPR)
Internal helper to get the object detection value.
static constexpr double VelTolerance
Velocity tolerance. Below this value we assume that the joint is stopped (rad/s). ...
TransportHints transport_hints
State handState
Hand state.
ros::CallbackQueue rosQueue
ROS callback queue.
boost::shared_ptr< PubQueue< T > > addPub()
ros::Publisher pubJointStates
Joint state publisher (rviz visualization).
void GetAndPublishJointState(const gazebo::common::Time &_curTime)
Publish Robotiq Joint state.
A plugin that implements the Robotiq 3-Finger Adaptative Gripper. The plugin exposes the next paramet...
boost::scoped_ptr< ros::NodeHandle > rosNode
ROS NodeHandle.
static const std::string DefaultLeftTopicCommand
Default topic name for sending control updates to the left hand.
bool IsHandFullyOpen()
Checks if the hand is fully open. return True when all the fingers are fully open or false otherwise...
static const std::string DefaultRightTopicState
Default topic name for receiving state updates from the right hand.
bool GetAndPushBackJoint(const std::string &_jointName, gazebo::physics::Joint_V &_joints)
Internal helper to reduce code duplication. If the joint name is found, a pointer to the joint is add...
boost::thread callbackQueueThread
ROS callback queue thread.
void RosQueueThread()
ROS callback queue thread.
void startServiceThread()
ros::Subscriber subHandleCommand
ROS control interface.
PubQueue< sensor_msgs::JointState >::Ptr pubJointStatesQueue
ROS publisher queue for joint states.
void StopHand()
Stop the fingers.
boost::shared_ptr< void > VoidPtr
virtual ~RobotiqHandPlugin()
Destructor.
gazebo::common::PID posePID[NumJoints]
PIDs used to control the finger positions.
uint8_t GetCurrentPosition(const gazebo::physics::JointPtr &_joint)
Internal helper to get the actual position of the finger.
bool VerifyCommand(const robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput::ConstPtr &_command)
Verify that all the command fields are within the correct range.
void UpdateStates()
Update the controller.
void ReleaseHand()
Fully open the hand at half of the maximum speed.
RobotiqHandPlugin()
Constructor.
robotiq_3f_gripper_articulated_msgs::Robotiq3FGripperRobotOutput handleCommand
HandleControl message. Originally published by user but some of the fields might be internally modifi...