Преглед на файлове

修改键盘控制文件注释

jally преди 4 години
родител
ревизия
5d3b133b82
променени са 1 файла, в които са добавени 14 реда и са изтрити 30 реда
  1. 14 30
      src/teleop_twist_keyboard/teleop_twist_keyboard.py

+ 14 - 30
src/teleop_twist_keyboard/teleop_twist_keyboard.py

@@ -4,8 +4,9 @@
 # Copyright: 2016-2020 wwww.corvin.cn ROS小课堂
 # Description: 通过键盘遥控小车行进、抓取。
 # History:
-#   20200317 增加小车抓取功能 by jally
+#   20200317 增加小车抓取功能
 #   20200408 增加小车可通过“7”“8”数字键控制夹爪张开闭合角度
+#   20200410 修改小车可通过“1”“2”数字键控制夹爪上下移动,“4”“5”张开闭合一定角度
 
 from __future__ import print_function
 
@@ -41,11 +42,10 @@ anything else : stop
 q/z : increase/decrease max speeds by 10%
 w/x : increase/decrease only linear speed by 10%
 e/c : increase/decrease only angular speed by 10%
-7/8 : increase/decrease angle by 5°
+4/5 : increase/decrease gripper angle by 5°
 
-1 : open the gripper and down
-2 : stop
-3 : close the gripper and up
+1 : arm go up
+2 : arm go dowm
 4 : open the gripper
 5 : close the gripper
 
@@ -82,15 +82,6 @@ speedBindings={
         'c':(1,.9),
     }
 
-
-#gripperBindings={
-#        '1':(),
-#        '2':(),
-#        '3':(),
-#        '4':(),
-#        '5':(),
-#    }
-
 gripperupBindings={
         '1':(),
     }
@@ -119,14 +110,14 @@ def angles(angle):
     return "currently:\tangle %s " % (angle)
 
 
-#调用service: mobilebase_arduino/gripper_control
+#调用service: mobilebase_arduino/gripper_control控制夹爪升降
+#调用service: mobilebase_arduino/gripper_angle控制夹爪开闭
 def client_srv():
     rospy.wait_for_service("mobilebase_arduino/gripper_control")
     rospy.wait_for_service("mobilebase_arduino/gripper_angle")
     try:
         gripper_client = rospy.ServiceProxy("mobilebase_arduino/gripper_control",GripperControl)
         gripper2_client = rospy.ServiceProxy("mobilebase_arduino/gripper_angle",GripperAngle)
-#        resp = gripper_client.call(int(key))
         resp = gripper_client.call(command)
         resp = gripper2_client.call(angle)
     except rospy.ServiceException, e:
@@ -168,23 +159,17 @@ if __name__=="__main__":
                 if (status == 14):
                     print(msg)
                 status = (status + 1) % 15           
-#            elif key in gripperBindings.keys():
-#                x = 0
-#                y = 0
-#                z = 0
-#                th = 0
-#                client_srv()
             elif key in gripperupBindings.keys():
                 x = 0
                 y = 0
                 z = 0
                 th = 0
                 command = 3
-                print("currently:\tgo up")
+                #print("currently:\tgo up")
                 client_srv()
-                time.sleep(0.2)
+                time.sleep(0.3)
                 command = 2
-                print("currently:\tstop !")
+                #print("currently:\tstop !")
                 client_srv()          
             elif key in gripperdownBindings.keys():
                 x = 0
@@ -192,11 +177,11 @@ if __name__=="__main__":
                 z = 0
                 th = 0
                 command = 1
-                print("currently:\tgo down")
+                #print("currently:\tgo down")
                 client_srv()
-                time.sleep(0.2)
+                time.sleep(0.3)
                 command = 2
-                print("currently:\tstop !")
+                #print("currently:\tstop !")
                 client_srv()
             elif key in gripperopenBindings.keys():
                 x = 0
@@ -215,8 +200,7 @@ if __name__=="__main__":
                 print(angles(angle))
                 if (angle <= 65 and angle >0):
                     angle = angle + grippercloseBindings[key]
-                    client_srv()
-             
+                    client_srv()         
             else:
                 x = 0
                 y = 0