39 Command-line interface for sending simple commands to a ROS node controlling a 2F gripper. 41 This serves as an example for publishing messages on the 'Robotiq2FGripperRobotOutput' topic using the 'Robotiq2FGripper_robot_output' msg type for sending commands to a 2F gripper. 44 import roslib; roslib.load_manifest(
'robotiq_2f_gripper_control')
46 from robotiq_2f_gripper_control.msg
import _Robotiq2FGripper_robot_output
as outputMsg
47 from time
import sleep
51 """Update the command according to the character entered by the user.""" 54 command = outputMsg.Robotiq2FGripper_robot_output();
61 command = outputMsg.Robotiq2FGripper_robot_output(); 72 command.rPR = int(char)
105 """Ask the user for a command to send to the gripper.""" 107 currentCommand =
'Simple 2F Gripper Controller\n-----\nCurrent command:' 108 currentCommand +=
' rACT = ' + str(command.rACT)
109 currentCommand +=
', rGTO = ' + str(command.rGTO)
110 currentCommand +=
', rATR = ' + str(command.rATR)
111 currentCommand +=
', rPR = ' + str(command.rPR )
112 currentCommand +=
', rSP = ' + str(command.rSP )
113 currentCommand +=
', rFR = ' + str(command.rFR )
118 strAskForCommand =
'-----\nAvailable commands\n\n' 119 strAskForCommand +=
'r: Reset\n' 120 strAskForCommand +=
'a: Activate\n' 121 strAskForCommand +=
'c: Close\n' 122 strAskForCommand +=
'o: Open\n' 123 strAskForCommand +=
'(0-255): Go to that position\n' 124 strAskForCommand +=
'f: Faster\n' 125 strAskForCommand +=
'l: Slower\n' 126 strAskForCommand +=
'i: Increase force\n' 127 strAskForCommand +=
'd: Decrease force\n' 129 strAskForCommand +=
'-->' 131 return raw_input(strAskForCommand)
134 """Main loop which requests new commands and publish them on the Robotiq2FGripperRobotOutput topic.""" 135 rospy.init_node(
'Robotiq2FGripperSimpleController')
137 pub = rospy.Publisher(
'Robotiq2FGripperRobotOutput', outputMsg.Robotiq2FGripper_robot_output)
139 command = outputMsg.Robotiq2FGripper_robot_output();
141 while not rospy.is_shutdown():
150 if __name__ ==
'__main__':
def askForCommand(command)
def genCommand(char, command)