树莓派连接接收机使用pigpio库读取PWM波脉宽实现与遥控器的远程通信

it2023-11-12  72

树莓派连接接收机使用pigpio库读取PWM波脉宽实现与遥控器的远程通信

一:pigpio库简介 pigpio是一个用于树莓派的库,它允许控制树莓派的通用输入输出(GPIO)引脚。 它的下载与安装步骤请参考:http://abyz.me.uk/rpi/pigpio/download.html 它提供了c语言风格与python语言风格的库函数,我们可以调用相关的库函数实现跟GPIO相关的操作。 二:读取PWM脉宽相关的几个库函数 callback函数用来捕获引脚上的电平变化,可以利用这个函数来读取脉冲宽度,其更详细的解释见http://abyz.me.uk/rpi/pigpio/python.html#callback。 例如: cb1=pi.callback(4,pigpio.EITHER_EDGE,mycallback1) 其含义为:4号IO口边沿(电平状态由低变高或者由高变低)触发回调函数mycallback1。

def mycallback1(gpio,level,tick): in_callback(0,gpio,level,tick) 进入mycallback1这个回调函数后,会将IO引脚,触发此次回调函数的电平状态以及当前的时间戳当成函数参数传递进来,此处我们定义了 in_callback(0,gpio,level,tick)函数将数组下标传入另一个函数in_callback。

def in_callback(argu,gpio,level,tick)在该函数中,我们获取此次捕获的高电平时间,更详细的实现过程见代码。

三:通过读取接收机的PWM信号实现与遥控器的远程通信 很多人对如何处理遥控器的信号可能感觉很复杂,其实不然,我们实际需要做的只是读取机载端的接收机产生的PWM脉宽信号(此处使用的模式是PWM型),关于接收机其它的工作模式更详细的解释可以参考https://blog.csdn.net/mao_hui_fei/article/details/85726320。 一般来说当你将遥控器某一摇杆摆动到最低位置时,其PWM波的脉宽为1000多一点,当其处于最高位是,其脉宽为1900左右,所以你可以通过读取PWM波的脉宽来感知你摇杆的位置进行遥控。 那么如何获取PWM波的脉宽,我们通过捕获PWM波上升沿和下降沿之间的时间间隔就可以得到其脉冲宽度。 具体的实现方式如下:

#!/usr/bin/env python #导入相关的库文件 #我们这里通过捕获PWM波脉冲宽度获取遥控器的控制信号,进而将其映射为移动小车的速度, #并通过ROS操作系统以cmd_vel话题twist消息的形式发布出去 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=[None,None,None] #定义回调函数 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 #打印当前速度 def vels(speedx,speedy,turn): return "currently:\tspeedx %s\tspeedy %s\tturn %s " % (speedx,speedy,turn)''' if __name__=='__main__': speedx = 0; speedy = 0; angular = 0; rospy.init_node('remote_control') pub = rospy.Publisher('cmd_vel', Twist, queue_size=100) rate=rospy.Rate(60) #此处的IO引脚号通过Broadcom number定义 cb1=pi.callback(17,pigpio.EITHER_EDGE,mycallback1) cb2=pi.callback(27,pigpio.EITHER_EDGE,mycallback2) cb3=pi.callback(27,pigpio.EITHER_EDGE,mycallback3) try: while not rospy.is_shutdown(): #速度单位,mm/s speedx = map_range(diff[0],second_range=[-300,300]) speedy = map_range(diff[1],second_range=[-300,300]) angular = map_range(diff[2],second_range=[-40,40]) #速度较小时,直接设置为0 if speedx < 40 and speedx >-40: speedx = 0; if speedy < 40 and speedy >-40: speedy = 0; if angular < 2 and angular >-2: angular = 0; #映射发布速度 twist = Twist() twist.linear.x = speedx twist.linear.y = speedy twist.linear.z = 0 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = angular pub.publish(twist) rate.sleep() except rospy.ROSInterruptException: pass 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)
最新回复(0)