baseRobotiq2FGripper.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Robotiq, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Robotiq, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 # Copyright (c) 2012, Robotiq, Inc.
34 # Revision $Id$
35 
36 """@package docstring
37 Module baseRobotiq2FGripper: defines a base class for handling command and status of the Robotiq 2F gripper.
38 
39 After being instanciated, a 'client' member must be added to the object. This client depends on the communication protocol used by the Gripper. As an example, the ROS node 'Robotiq2FGripperTcpNode.py' instanciate a robotiqbaseRobotiq2FGripper and adds a client defined in the module comModbusTcp.
40 """
41 
42 from robotiq_2f_gripper_control.msg import _Robotiq2FGripper_robot_input as inputMsg
43 from robotiq_2f_gripper_control.msg import _Robotiq2FGripper_robot_output as outputMsg
44 
46  """Base class (communication protocol agnostic) for sending commands and receiving the status of the Robotic 2F gripper"""
47 
48  def __init__(self):
49 
50  #Initiate output message as an empty list
51  self.message = []
52 
53  #Note: after the instantiation, a ".client" member must be added to the object
54 
55  def verifyCommand(self, command):
56  """Function to verify that the value of each variable satisfy its limits."""
57 
58  #Verify that each variable is in its correct range
59  command.rACT = max(0, command.rACT)
60  command.rACT = min(1, command.rACT)
61 
62  command.rGTO = max(0, command.rGTO)
63  command.rGTO = min(1, command.rGTO)
64 
65  command.rATR = max(0, command.rATR)
66  command.rATR = min(1, command.rATR)
67 
68  command.rPR = max(0, command.rPR)
69  command.rPR = min(255, command.rPR)
70 
71  command.rSP = max(0, command.rSP)
72  command.rSP = min(255, command.rSP)
73 
74  command.rFR = max(0, command.rFR)
75  command.rFR = min(255, command.rFR)
76 
77  #Return the modified command
78  return command
79 
80  def refreshCommand(self, command):
81  """Function to update the command which will be sent during the next sendCommand() call."""
82 
83  #Limit the value of each variable
84  command = self.verifyCommand(command)
85 
86  #Initiate command as an empty list
87  self.message = []
88 
89  #Build the command with each output variable
90  #To-Do: add verification that all variables are in their authorized range
91  self.message.append(command.rACT + (command.rGTO << 3) + (command.rATR << 4))
92  self.message.append(0)
93  self.message.append(0)
94  self.message.append(command.rPR)
95  self.message.append(command.rSP)
96  self.message.append(command.rFR)
97 
98  def sendCommand(self):
99  """Send the command to the Gripper."""
100 
101  self.client.sendCommand(self.message)
102 
103  def getStatus(self):
104  """Request the status from the gripper and return it in the Robotiq2FGripper_robot_input msg type."""
105 
106  #Acquire status from the Gripper
107  status = self.client.getStatus(6);
108 
109  #Message to output
110  message = inputMsg.Robotiq2FGripper_robot_input()
111 
112  #Assign the values to their respective variables
113  message.gACT = (status[0] >> 0) & 0x01;
114  message.gGTO = (status[0] >> 3) & 0x01;
115  message.gSTA = (status[0] >> 4) & 0x03;
116  message.gOBJ = (status[0] >> 6) & 0x03;
117  message.gFLT = status[2]
118  message.gPR = status[3]
119  message.gPO = status[4]
120  message.gCU = status[5]
121 
122  return message
123 


robotiq_2f_gripper_control
Author(s): Nicolas Lauzier (Robotiq inc.)
autogenerated on Tue Jun 1 2021 02:29:54