42
42
This serves as an example for publishing messages on the 'Robotiq3FGripperRobotOutput' topic using the 'Robotiq3FGripper_robot_output' msg type for sending commands to a 3F gripper gripper. In this example, only the simple control mode is implemented. For using the advanced control mode, please refer to the Robotiq support website (support.robotiq.com).
43
43
"""
44
44
45
- import roslib ; roslib .load_manifest ('robotiq_3f_gripper_control' )
45
+ from __future__ import print_function
46
+
47
+ import roslib ;
48
+
49
+ roslib .load_manifest ('robotiq_3f_gripper_control' )
46
50
import rospy
47
- from robotiq_3f_gripper_control .msg import _Robotiq3FGripper_robot_output as outputMsg
48
- from time import sleep
51
+ from robotiq_3f_gripper_articulated_msgs .msg import Robotiq3FGripperRobotOutput
49
52
50
53
51
54
def genCommand (char , command ):
52
- """Update the command according to the character entered by the user."""
53
-
55
+ """Update the command according to the character entered by the user."""
56
+
54
57
if char == 'a' :
55
- command = outputMsg . Robotiq3FGripper_robot_output ();
58
+ command = Robotiq3FGripperRobotOutput ();
56
59
command .rACT = 1
57
60
command .rGTO = 1
58
61
command .rSPA = 255
59
62
command .rFRA = 150
60
63
61
64
if char == 'r' :
62
- command = outputMsg . Robotiq3FGripper_robot_output ();
65
+ command = Robotiq3FGripperRobotOutput ();
63
66
command .rACT = 0
64
67
65
68
if char == 'c' :
@@ -70,79 +73,78 @@ def genCommand(char, command):
70
73
71
74
if char == 'b' :
72
75
command .rMOD = 0
73
-
76
+
74
77
if char == 'p' :
75
78
command .rMOD = 1
76
-
79
+
77
80
if char == 'w' :
78
81
command .rMOD = 2
79
-
82
+
80
83
if char == 's' :
81
84
command .rMOD = 3
82
85
83
- #If the command entered is a int, assign this value to rPRA
84
- try :
86
+ # If the command entered is a int, assign this value to rPRA
87
+ try :
85
88
command .rPRA = int (char )
86
89
if command .rPRA > 255 :
87
90
command .rPRA = 255
88
91
if command .rPRA < 0 :
89
92
command .rPRA = 0
90
93
except ValueError :
91
- pass
92
-
94
+ pass
95
+
93
96
if char == 'f' :
94
97
command .rSPA += 25
95
98
if command .rSPA > 255 :
96
99
command .rSPA = 255
97
-
100
+
98
101
if char == 'l' :
99
102
command .rSPA -= 25
100
103
if command .rSPA < 0 :
101
104
command .rSPA = 0
102
105
103
-
104
106
if char == 'i' :
105
107
command .rFRA += 25
106
108
if command .rFRA > 255 :
107
109
command .rFRA = 255
108
-
110
+
109
111
if char == 'd' :
110
112
command .rFRA -= 25
111
113
if command .rFRA < 0 :
112
114
command .rFRA = 0
113
115
114
116
return command
115
-
117
+
116
118
117
119
def askForCommand (command ):
118
- """Ask the user for a command to send to the gripper."""
120
+ """Ask the user for a command to send to the gripper."""
119
121
120
- currentCommand = 'Simple 3F gripper Controller\n -----\n Current command:'
121
- currentCommand += ' rACT = ' + str (command .rACT )
122
+ currentCommand = 'Simple 3F gripper Controller\n -----\n Current command:'
123
+ currentCommand += ' rACT = ' + str (command .rACT )
122
124
currentCommand += ', rMOD = ' + str (command .rMOD )
123
125
currentCommand += ', rGTO = ' + str (command .rGTO )
124
126
currentCommand += ', rATR = ' + str (command .rATR )
125
- ## currentCommand += ', rGLV = ' + str(command.rGLV)
126
- ## currentCommand += ', rICF = ' + str(command.rICF)
127
- ## currentCommand += ', rICS = ' + str(command.rICS)
127
+ ## currentCommand += ', rGLV = ' + str(command.rGLV)
128
+ ## currentCommand += ', rICF = ' + str(command.rICF)
129
+ ## currentCommand += ', rICS = ' + str(command.rICS)
128
130
currentCommand += ', rPRA = ' + str (command .rPRA )
129
131
currentCommand += ', rSPA = ' + str (command .rSPA )
130
132
currentCommand += ', rFRA = ' + str (command .rFRA )
131
133
132
- #We only show the simple control mode
133
- ## currentCommand += ', rPRB = ' + str(command.rPRB)
134
- ## currentCommand += ', rSPB = ' + str(command.rSPB)
135
- ## currentCommand += ', rFRB = ' + str(command.rFRB)
136
- ## currentCommand += ', rPRC = ' + str(command.rPRC)
137
- ## currentCommand += ', rSPC = ' + str(command.rSPC)
138
- ## currentCommand += ', rFRC = ' + str(command.rFRC)
139
- ## currentCommand += ', rPRS = ' + str(command.rPRS)
140
- ## currentCommand += ', rSPS = ' + str(command.rSPS)
141
- ## currentCommand += ', rFRS = ' + str(command.rFRS)
134
+ # We only show the simple control mode
135
+ ## currentCommand += ', rPRB = ' + str(command.rPRB)
136
+ ## currentCommand += ', rSPB = ' + str(command.rSPB)
137
+ ## currentCommand += ', rFRB = ' + str(command.rFRB)
138
+ ## currentCommand += ', rPRC = ' + str(command.rPRC)
139
+ ## currentCommand += ', rSPC = ' + str(command.rSPC)
140
+ ## currentCommand += ', rFRC = ' + str(command.rFRC)
141
+ ## currentCommand += ', rPRS = ' + str(command.rPRS)
142
+ ## currentCommand += ', rSPS = ' + str(command.rSPS)
143
+ ## currentCommand += ', rFRS = ' + str(command.rFRS)
142
144
143
- print currentCommand
145
+ print ( currentCommand )
144
146
145
- strAskForCommand = '-----\n Available commands\n \n '
147
+ strAskForCommand = '-----\n Available commands\n \n '
146
148
strAskForCommand += 'r: Reset\n '
147
149
strAskForCommand += 'a: Activate\n '
148
150
strAskForCommand += 'c: Close\n '
@@ -156,28 +158,28 @@ def askForCommand(command):
156
158
strAskForCommand += 'l: Slower\n '
157
159
strAskForCommand += 'i: Increase force\n '
158
160
strAskForCommand += 'd: Decrease force\n '
159
-
161
+
160
162
strAskForCommand += '-->'
161
163
162
164
return raw_input (strAskForCommand )
163
165
166
+
164
167
def publisher ():
165
168
"""Main loop which requests new commands and publish them on the Robotiq3FGripperRobotOutput topic."""
166
169
167
170
rospy .init_node ('Robotiq3FGripperSimpleController' )
168
-
169
- pub = rospy .Publisher ('Robotiq3FGripperRobotOutput' , outputMsg .Robotiq3FGripper_robot_output )
170
171
171
- command = outputMsg .Robotiq3FGripper_robot_output ();
172
+ pub = rospy .Publisher ('Robotiq3FGripperRobotOutput' , Robotiq3FGripperRobotOutput )
173
+
174
+ command = Robotiq3FGripperRobotOutput ();
172
175
173
176
while not rospy .is_shutdown ():
177
+ command = genCommand (askForCommand (command ), command )
174
178
175
- command = genCommand (askForCommand (command ), command )
176
-
177
179
pub .publish (command )
178
180
179
181
rospy .sleep (0.1 )
180
-
182
+
181
183
182
184
if __name__ == '__main__' :
183
185
publisher ()
0 commit comments