ROS機器人Diego 1#製作(十五)機械臂的控制---通過鍵盤控制機械臂舵機

更多創客作品,請關注筆者網站園丁鳥,蒐集全球極具創意,且有價值的創客作品
ROS機器人知識請關注,diegorobot
業餘時間完成的一款在線統計過程分析工具SPC,及SPC知識分享網站qdo


爲了便於調試,特意寫了一個通過鍵盤控制機械臂舵機的代碼,來調試舵機,代碼是基於teleop_twist_keyboard修改的。在arduino_node.py中已經聲明瞭舵機讀和寫的ROS Service:

        # A service to position a PWM servo
        rospy.Service('~servo_write', ServoWrite, self.ServoWriteHandler)
        
        # A service to read the position of a PWM servo
        rospy.Service('~servo_read', ServoRead, self.ServoReadHandler)

配合上一篇微博中arduino端的舵機驅動,我們只需要實現這兩個ROS Service的client就可以控制舵機了,具體原理請看代碼中的註釋代碼如下:

#!/usr/bin/env python
import roslib; roslib.load_manifest('teleop_twist_keyboard')
import rospy

from geometry_msgs.msg import Twist
from ros_arduino_msgs.srv import *
from math import pi as PI
import sys, select, termios, tty

msg = """
Reading from the keyboard  and Publishing to Twist, Servo or sensor!
---------------------------
Moving around:
   u    i    o
   j    k    l

, : up (+z)
. : down (-z)
m : stop

----------------------------
Left arm servo control:控制機器人左臂,每次調整0.09弧度
+   1   2   3   4   5   6
-   q   w   e   r   t   y  
----------------------------
Right arm servo control:控制機器人右臂,每次調整0.09弧度
+   a   s   d   f   g   h
-   z   x   c   v   b   n 

p : init the servo 初始化舵機

CTRL-C to quit
"""

moveBindings = {
		'i':(1,0,0,0),
		'o':(1,0,0,1),
		'j':(-1,0,0,-1),
		'l':(-1,0,0,1),
		'u':(1,0,0,-1),
		'k':(-1,0,0,0),
		',':(0,0,1,0),
		'.':(0,0,-1,0),
	       }

#右臂舵機的控制數組,1表示增加0.09弧度,0表示減少0.09弧度
rightArmServo={
      	        '1':(0,1),
	        '2':(1,1),
	        '3':(2,1),
	        '4':(3,1),
	        '5':(4,1),
	        '6':(5,1),
	        'q':(0,0),
	        'w':(1,0),
	        'e':(2,0),
	        'r':(3,0),
	        't':(4,0),
	        'y':(5,0),
	      }

#左臂舵機的控制數組,1表示增加0.09弧度,0表示減少0.09弧度
leftArmServo={
	        'a':(6,1),
	        's':(7,1),
	        'd':(8,1),
	        'f':(9,1),
	        'g':(10,1),
	        'h':(11,1),
	        'z':(6,0),
	        'x':(7,0),
	        'c':(8,0),
	        'v':(9,0),
	        'b':(10,0),
	        'n':(11,0),
	      }

#手臂臂舵機的控制命令數組	      
armCmd={
	'[':(0,1),#左臂初始化
	']':(1,1),#右臂初始化
       }

def getradians(angle):
	return PI*angle/180


def getKey():
	tty.setraw(sys.stdin.fileno())
	select.select([sys.stdin], [], [], 0)
	key = sys.stdin.read(1)
	termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
	return key

#舵機當前位置讀取,調用servo_read service
def servoRead(servoNum):
	rospy.wait_for_service('/arduino/servo_read')
	try:
	    readServo=rospy.ServiceProxy('/arduino/servo_read',ServoRead)
	    return readServo(servoNum)
        except rospy.ServiceException, e:
            print "Service call failed: %s"%e

#舵機位置寫,根據舵機標號設置舵機的位置0~π,注意這裏的value對應的是弧度        
def servoWrite(servoNum, value):
        rospy.wait_for_service('/arduino/servo_write')
	try:
	    servo_write=rospy.ServiceProxy('/arduino/servo_write',ServoWrite)
	    servo_write(servoNum,value)
	    print servoNum
            print value
        except rospy.ServiceException, e:
            print "Service call failed: %s"%e

#初始化右臂舵機角度,要根據實際情況調整舵機角度     
def initRightArm():
	servoWrite(0,getradians(60)) 
	servoWrite(1,getradians(80))
	servoWrite(2,getradians(90))
	servoWrite(3,getradians(90))
	servoWrite(4,getradians(90))
	servoWrite(5,getradians(90))

#初始化左臂舵機角度,要根據實際情況調整舵機角度	
def initLeftArm():	
	servoWrite(6,getradians(90))
	servoWrite(7,getradians(90))
	servoWrite(8,getradians(90))
	servoWrite(9,getradians(90))
	servoWrite(10,getradians(90))
	servoWrite(11,getradians(90))    
	 
def vels(speed,turn):
	return "currently:\tspeed %s\tturn %s " % (speed,turn)

if __name__=="__main__":
    	settings = termios.tcgetattr(sys.stdin)
	
	pub = rospy.Publisher('cmd_vel', Twist, queue_size = 1)
	rospy.init_node('teleop_twist_keyboard')

	speed = rospy.get_param("~speed", 0.5)
	turn = rospy.get_param("~turn", 1.0)
	x = 0
	y = 0
	z = 0
	th = 0
	status = 0

	try:
		print msg
		print vels(speed,turn)
		while(1):
			key = getKey()
			print key
			if key in moveBindings.keys():
				x = moveBindings[key][0]
				y = moveBindings[key][1]
				z = moveBindings[key][2]
				th = moveBindings[key][3]
			elif key in leftArmServo.keys():#左臂舵機控制
			    value=servoRead(leftArmServo[key][1]).value			    
			    if(leftArmServo[key][1]==0):
			        value=value-getradians(5)
			        if value<=0:
			           value=0
			    else:
			        value=value+getradians(5)
			        if value>=PI:
			           value=PI
			    servoWrite(leftArmServo[key][0], value)
			elif key in rightArmServo.keys():#右臂舵機控制
			    value=servoRead(rightArmServo[key][1]).value			    
			    if(rightArmServo[key][1]==0):
			        value=value-getradians(5)
			        if value<=0:
			           value=0
			    else:
			        value=value+getradians(5)
			        if value>=PI:
			           value=PI
			    servoWrite(rightArmServo[key][0], value)
			elif key in armCmd.keys():#舵機初始化
			    if(armCmd[key][0]==0):
			        initRightArm()
			    elif(armCmd[key][0]==1):
			        initLeftArm()
			else:
				x = 0
				y = 0
				z = 0
				th = 0
				if (key == '\x03'):
					break

			twist = Twist()
			twist.linear.x = x*speed; twist.linear.y = y*speed; twist.linear.z = z*speed;
			twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = th*turn
			pub.publish(twist)

	except BaseException,e:
		print e

	finally:
		twist = Twist()
		twist.linear.x = 0; twist.linear.y = 0; twist.linear.z = 0
		twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0
		pub.publish(twist)

    		termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)

這裏需要強調一下硬件的使用過程中,一定要保證供電的功率足夠,否則的話會出現串口通信異常,機械臂亂動等現象,這都是電源供電不足的問題導致的。

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章