树莓派使用pigpio库产生PWM波实现舵机控制
一:pigpio库简介 pigpio是一个用于树莓派的库,它允许控制树莓派的通用输入输出(GPIO)引脚。 它的下载与安装步骤请参考:http://abyz.me.uk/rpi/pigpio/download.html 它提供了c语言风格与python语言风格的库函数,我们可以调用相关的库函数实现跟GPIO相关的操作。 与PWM操作相关的几个函数的详细解释可以参考http://abyz.me.uk/rpi/pigpio/python.html#get_PWM_frequency
二:产生PWM波相关的几个库函数 更详细的解释请参考: http://abyz.me.uk/rpi/pigpio/python.html 三:具体的实现过程 此处实现了使用遥控器控制舵机1,2的旋转角度,与舵机3的连续旋转/反向旋转/与停止。 关于如何获取遥控器信号可参考上一篇博客。
#!/usr/bin/env python
#导入相关的库文件
import rospy
from std_msgs.msg import String
from geometry_msgs.msg import Twist
import sys, select, termios, tty
#导入pigpio库
import pigpio
import time
#建立实体化对象
pi=pigpio.pi()
#tick_0用于存储低电平捕获的时间戳
tick_0=[None,None,None]
#tick_1用于存储高电平捕获的时间戳
tick_1=[None,None,None]
#diff用于存储脉宽
diff=[1500,None,1500]
#定义回调函数
def in_callback(argu,gpio,level,tick):
#如果是低电平,则说明下降沿到来,通过数组diff将两次捕获的时间差存储起来
if level==0:
#存储此次时间戳
tick_0[argu]=tick
#如果高电平捕获的时间戳不为0
if tick_1[argu] is not None:
#获取两次的时间戳差值,即为高电平持续时间,即为脉冲宽度
diff[argu]=pigpio.tickDiff(tick_1[argu],tick)
#打印
print "number: " + str(argu) + " high for " + str(diff)+" microseconds"
#如果是高电平,存储此次时间戳
else:
tick_1[argu]=tick
def mycallback1(gpio,level,tick):
in_callback(0,gpio,level,tick)
def mycallback2(gpio,level,tick):
in_callback(1,gpio,level,tick)
def mycallback3(gpio,level,tick):
in_callback(2,gpio,level,tick)
#将遥控器获得的控制信号映射为舵机的转角
def map_range(x,first_range=[1000,2000],second_range=[100,500]):
x = second_range[0]+(int(str(x))-first_range[0])*(second_range[1]-second_range[0])/(first_range[1]-first_range[0])
return x
if __name__=='__main__':
settings = termios.tcgetattr(sys.stdin)
angle1 =14;
angle2 = 460;
angle3 = 0;
#产生PWM波,设置频率范围与角度
pi.write(26, 0)
pi.set_PWM_frequency(26, 50)
pi.set_PWM_range(26, 4000)
pi.set_PWM_dutycycle(26,angle1)
pi.write(20, 0)
pi.set_PWM_frequency(20, 50)
pi.set_PWM_range(20, 4000)
pi.set_PWM_dutycycle(20,angle2)
pi.write(16, 0)
pi.set_PWM_frequency(16, 50)
pi.set_PWM_range(16, 4000)
pi.set_PWM_dutycycle(16,angle3)
#初始化ROS节点
rospy.init_node('duoji_control')
rate=rospy.Rate(60)
cb1=pi.callback(13,pigpio.EITHER_EDGE,mycallback1)
cb9=pi.callback(19,pigpio.EITHER_EDGE,mycallback2)
cb4=pi.callback(22,pigpio.EITHER_EDGE,mycallback3)
try:
while not rospy.is_shutdown():
angle1 = map_range(diff[0],second_range=[100,500])
pi.set_PWM_dutycycle(26,angle1)
angle2 = map_range(diff[1],second_range=[250,500])
pi.set_PWM_dutycycle(20,angle2)
if int(str(diff[2])) > 1700:
angle3= 450;
elif int(str(diff[2])) |