目录
一、实验内容
二、实验一 按键控制 LED 灯
2.1 硬件原理
2.2 软件设计原理
2.3软件实现
2.4实现效果
三、实验二 电机驱动
3.1 硬件原理
3.2 软件设计原理
3.3软件实现
3.4实现效果
四、实验三 循迹、碰撞转向、红外避障
4.1 硬件原理
4.2 软件原理
4.3软件实现
一、实验内容
1、检测开关性能和 LED 灯的性能
点亮LED灯,闪烁或常亮;两个开关分别控制灯的闪烁频率和灯的颜色。
2. 测试轮子转动的功能
小车可以开动;开关控制速度和方向变化。
3.智能小车实现
循线功能;避障功能;碰撞转向功能。
二、实验一 按键控制 LED 灯
2.1 硬件原理
(1)I/O 口设置
MSP432P401R 的每一组 I/O口都配有一定的寄存器用来控制I/O口的情况。
功能选择寄存器 PxSEL0 和 PxSEL1
每个端口的引脚可使用两个位来选择引脚功能:I/O 功能或 3 个可能的外设模块功能中的一个。
方向寄存器 PxDIR
当引脚的功能被配置为 I/O 端口时,PxDIR 寄存器中的每一位都将反映相应I/O 引脚的方向。当引脚的功能被配置为外设功能时,大多数情况下 PxDIR 寄存器也可以控制 I/O 端口的方向。但是,对于引脚的功能被设置为外设功能的情况,PxDIR 寄存器的每一位都必须按外设功能的要求进行设置。而对于某些第二功能,比如 eUSCI,I/O 端口的方向则由第二功能本身决定,而不是由 PxDIR 寄存器控制。
位 0:引脚为输入方向; 位 1:引脚为输出方向
上拉或下拉电阻使能寄存器 PxREN
PxREN 寄存器中的每一位都用于使能或者禁用相应 I/O 引脚的上拉或下拉电阻。PxREN 寄存器上的相应位用于选择上拉或下拉电阻。
位 0:禁用上拉/下拉电阻; 位 1:使能上拉/下拉电阻
输出寄存器 PxOUT
(1)当引脚的功能配置为 I/O 端口且方向为输出时,PxOUT 寄存器中的每一位将对应相应引脚的输出值。
位 0:输出为低; 位 1:输出为高
(2)若将引脚功能配置为 I/O 端口且方向为输入,在使能上拉或下拉电阻
时,则 PxOUT 寄存器中的相应位用于选择上拉或下拉电阻。
位 0:下拉; 位 1:上拉
驱动强度选择寄存器 PxDS
I/O 有两种类型:一种为常规的驱动强度,另一种为高驱动强度。大多数的I/O 具有常规驱动强度,而一些选定的 I/O 具有高驱动强度。PxDS 寄存器用于选择高驱动 I/O 的驱动强度。
位 0:具有高驱动强度的 I/O 被配置成常规驱动强度
位 1:具有高驱动强度的 I/O 被配置成高驱动强度
PxDS 寄存器对仅具有常规驱动强度的 I/O 无效。
(2)开关设置
开关 SW1、SW2 分别连接到 CPU 的 P1.1、P1.4 的两个 GPIO 口,四个发光二级管的阳极连接到 CPU 的 P2.0、P2.1、P2.2、P1.0 的四个 GPIO 口。SW1和 SW2 的状态可以作为输入信号,控制 LED 灯的颜色和闪烁。
SW1、SW2 开关接口图
本实验中开发板中有2个LED灯,通过色光混合的原理来实现不同的颜色。红绿蓝是自然界中的三基色,色光混合定律表明,通过红绿蓝三种颜色按照一定比例混合可以得到不同的颜色,本实验使用了这种原理,产生7种组合,对应7种不同的颜色。
(3)时钟配置
MSP432P401R微控制器上具有多个时钟源,分为内部时钟源与外部时钟源。内部时钟有可调内部数控振荡器 (DCO)、内部 ADC 振荡器 (CMODOS)、系统振荡器 (SYSOSC)、低频内部基准振荡器 (REFO) 和 VLO;外部时钟有高频晶振 (HFXT)、低频晶振 (LFXT)。其中DCO、HFXT、MODOSC 和 SYSOSC 为高频时钟源,而 LFXT、REFO 和 VLO 则为低频时钟源。REFO 是经工厂校准的内部低频时钟源,可以将其设定为生成 32.768kHz 或 128kHz 时钟。VLO 是一种功耗极低的低频振荡器,可提供9.4kHz的时钟(典型值)。LFXT 是一种低频晶体振荡器,能够提供 32.768kHz 时钟。HFXT是一种高频晶振振荡器,能够提供48MHz的时钟。电路原理图如下所示:
低频晶振电路
高频晶振电路
2.2 软件设计原理
初始化对应的输入输出端口,即设置P1.1、P1.4为输入端口,P2.0-P2.2 与P1.0 为输出端口。通过按下 SW1 或 SW2 改变输入,从而控制两个 LED 的颜色和闪烁间隔。本组设计的实验一中,当P1.4被按下时,跑马灯闪烁间隔可以在50ms 、1s和常亮三种模式下变换;当P1.1被按下时,每按下一次,变换一种颜色一共有7种颜色。
2.3软件实现
2.3.1.初始化
通过红绿蓝三种颜色按照一定比例混合可以得到不同的颜色,使用这个原理,产生7种组合,对应7种不同的颜色,用宏定义表示灯的颜色:
#define OFF 0x00
#define RED 0x01 //R
#define GREEN 0x02 //G
#define BLUE 0x04 //B
#define yellow 0x03 //RG-
#define sky 0x06 //-GB
#define white 0x07 //RGB
#define pink 0x05 //R-B
Clock_Init48MHz();//首先配置48MHz的时钟
Port1_Init();//初始化P1.1和P1.4为输入端口
文章来源地址https://www.toymoban.com/news/detail-520883.html
Port2_Init();//初始化P2.2-P2.0为输出端口
uint8_t status1=0x01;//用于保存颜色的状态
uint8_t num=0x00; //用于保存闪烁频率的状态
uint8_t status;//用于读取P1.1和P1.4端口的状态
2.3.2.运行主要函数
初始化完之后,就进入while(1){}循环运行。
通过累加的方式来改变状态,有7种颜色,则当status1为0x08是变为0x01,频率因为只写了三种,则直接采用求余数的方法num%3控制:
为防止多次计数改变状态,可采用while死循环:
通过switch (num%3)来进入不同频率模式闪烁:
通过Clock_Delay1ms(xxx);来控制一次亮或者灭的时长,可以使用两个Clock_Delay1ms(xxx);来形成不同占空比的亮灭效果,而我们设置的占空比为50%。
2.4实现效果
在板子上按下两个按键,可以观察到每一次按下P1.1,小车会切换一种颜色,七种颜色为一个循环,每一次按下P1.4,,小车会切换不同频率,因此成功实现实验一的功能。实验一功能实现图如下:
实验一功能实现图
三、实验二 电机驱动
3.1 硬件原理
(1)脉冲宽度调制
脉冲宽度调制(Pulse Width Modulation,PWM),指按照一定的规律改变脉冲序列的脉冲宽度(占空比值),调节输出量和波形的一种调制方式,常用来输出矩形 PWM 信号。要输出不同的模拟电压,就要用到PWM,通过改变IO口输出的方波的占空比从而获得使用数字信号模拟成的模拟电压信号。电压是以一种连接1或断开0的重复脉冲序列被夹到模拟负载上去的,连接即是直流供电输出,断开即是直流供电断开。通过对连接和断开时间的控制,理论上来讲,可以输出任意不大于最大电压值的模拟电压。
通过占空比改变模拟电压示意图
pwm的调节作用来源于对“占周期”的宽度控制,“占周期”变宽,输出的能量就会提高,通过阻容变换电路所得到的平均电压值也会上升,“占周期”变窄,输出的电压信号的电压平均值就会降低,通过阻容变换电路所得到的平均电压值也会下降。总的来说,PWM就是在合适的信号频率下,通过一个周期里改变占空比的方式来改变输出的有效电压。
在本控制系统中 PWM 用于电机转速的控制,通过改变 MSP432控制程序中的 GPIO 口 P2.6、P2.7 输出的 PWM 的占空比就可以调节两轮的转速。在一个周期内,增大占空比,就会增大高电平的比例,输出在电机上的电压会随之增大,电机转速也随之加快。MSP432 的控制程序一般是通过自有的定时器 A(Timer A)来输出 PWM。TimerA 定时器是一个配备了 5 个捕获/比较寄存器的 16 位定时器/计数器,支持多种捕获/比较,PWM 信号输出,间断计时,同时具备扩展中断功能。利用一个 TimerA 定时器最多可以同时输出 7 组不同的 PWM。而在本控制系统中只需要两组不同的 PWM 值来控制左右两轮的转速从而控制小车的运动状态。通过查阅 TI-RSLK 操作手册,控制电机运动状态的共有 6 个 GPIO 输出口:P1.6、P2.6、P3.6、P1.7、P2.7、P3.7。
(2)端口中断
在单片机中,对于CPU来说,当它在正常处理事件A时,突然发生了另一件事件B(中断发生)需要CPU去处理,这时CPU就会暂停处理事件A(中断响应),转而去处理事件B(中断服务)。当事件B处理完以后,再回到事件A原来中断的地方继续执行事件A(中断返回)。这一整个过程称为中断。而当中断过程B中,发生了另一个中断级别更高的中断事件C,则CPU又会中断当前的B转而去处理C,完毕后再回到B的断点继续处理,这称为中断的嵌套。中断的嵌套涉及到中断的优先级问题,有几个重要的概念:
中断响应过程:由中断管理系统处理突发事件的过程;
中断源:中断管理系统能够处理的突发事件;
中断请求:中断源向CPU提出的处理请求;
中断函数:针对中断源和中断请求提供的服务函数;
中断嵌套:在中断服务过程中执行更高级别的中断服务。
中断过程简图
中断可实现的功能主要有:1、分时操作:CPU可以使多个外设同时工作,并分时为各外设提供服务,从而大大提高了CPU的利用率和输入/输出的速度。2、实时处理:当计算机用于实时控制时,请求CPU提供服务是随机发生的。有了中断系统,CPU就可以立即响应并加以处理。3、故障处理:当计算机运行中出现如电源断电、存储器校验出错、运算溢出等错误时,CPU可及时转去执行故障处理程序,减小或消除故障产生的影响。
中断配置:
(1)中断边沿选择寄存器PxIES
PxIES寄存器的每一位选择都对应着I/O引脚的中断边沿。
位0:PxIFG标志设置为由低电平→高电平的转换;
位1:PxIFG标志设置为由高电平→低电平的转换;
(2)中断使能寄存器PxIE
PxIE寄存器的每一位使能都对应着PxIFG的中断标志
位0:禁用中断; 位1:使能中断
(3)中断标志寄存器PxIFG
PxIFG寄存器的每一位都是其相应I/O引脚的中断标志,并且当所选择的输入信号出现在引脚上时,中断标志将被置位。若PxIE寄存器的相应位置位,则所有PxIFG寄存器的中断标志将发出一个中断请求。此外,也可以通过使用软件将PxIFG寄存器的中断标志置位的方法来启动中断。
位0:无中断挂起; 位1:中断挂起
3.2 软件设计原理
在实现用开关控制小车转速以及前进方向的时候,驱动器通过 MSP432P401R产生的 PWM 波控制电机的状态,实现小车的启动、左右转弯、前进后退、掉头、停止等功能,并且通过中断开关控制小车行进的方向和速度。按下P1.1时,改变小车运行的方向。按下P1.4,改变小车运行的速度。P1.1和P1.4同时按下时,小车停止。
3.3软件实现
电机驱动和实验一的按键控制 LED 灯的方式类似,但是此次我们将按键配置为了中断,相比于实验一可以使得按键更加灵敏,控制的速度更快。
3.3.1.初始化
Clock_Init48MHz();//首先配置48MHz的时钟
Motor_Init();//初始化电机端,将P1.6,P1.7,P3.6, P3.7为输出端口,用于驱动电机
PWM_Init34(uint16_t period,uint16_t duty3,uint16_t duty4)//PWM初始化, 实现小车的电机驱动控制
EdgeTrigger_Init();//初始化中断,将P1.1和P1.4配置为中断
改变小车的运动状态,我们调用不同运动函数来改变小车的状态,以左转函数为例:Motor_Left(uint16_t leftDuty, uint16_t rightDuty),其中参数 leftDuty 和 rightDuty 分别改变左轮和右轮的占空比,从而实现对电机速度的控制,数值越大,电机运动速度越快。左轮后退,右轮前进,可实现左转功能,左轮前进,右轮后退,可实现右转功能。
中断服务函数,在中断服务函数中对按键按下的次数进行累加,改变控制电机转动状态的寄存器变量,这样可以很好地改变电机的状态,不需要多次触发中断,影响小车的运行
3.3.2.运行主要函数
通过b来选择4种速度,通过c来选择5种转向
除了用switch ()来选择外,还可以直接用if;else if来选择,将转速和转向分开来写:
3.4实现效果
在板子上按下两个按键,可以观察到每一次按下P1.1,小车切换转速;每一次按下P1.4,,小车会切换运行方向,且按键相较于实验一更加灵敏,因此成功实现实验二的功能。实验二的功能实现图
如下:
实验二功能实现图
四、实验三 循迹、碰撞转向、红外避障
4.1 硬件原理
4.1.1 循迹
红外自动循迹是指小车在白色地板上循黑线行走,由于黑线和白色地板对光线的反射系数不同,可以根据接收到的反射光的强弱来判断“道路”。通常采取的方法是红外探测法。红外探测法,即利用红外线在不同颜色的物体表面具有不同的反射性质的特点,在小车行驶过程中不断地向地面发射红外光,当红外光遇到白色纸质地板时发生漫反射,反射光被装在小车上的接收管接收;如果遇到黑线则红外光被吸收,小车上的接收管接收不到红外光。单片机就是否收到反射回来的红外光为依据来确定黑线的位置和小车的行走路线。
本设计采用 JN_LSA_2RSLKBO1 线阵传感器,包含 8 个传感器,每个传感器都对应二进制数,如果看到黑色则返回 1,如果看到白色则返回 0。如果小车正确地定位在线上,中间传感器将看到黑色;如果小车向左或向右偏离,则一个或多个外侧传感器将看到黑色;如果小车完全脱离轨迹,则所有传感器都将看到白色。MSP432P401R 通过对传感器返回的数据进行分析,从而控制小车的行进状态,修正小车运动路径。
JN_LSA_2RSLKBO1 线阵传感器
红外循迹传感器对路面进行实时检测,将八个传感器返回的 8 位二进制数组合成一个位置参数。我们将小车的位置定义为从传感器到线的距离,我们使用的循迹模块宽约 66 毫米,每两个传感器间距为 9.5mm,小车中心在传感器 4 和5之间对齐,以 0.1mm 为单位定义 8 个距离值,从 U1 到 U8 依次定义为 332、237、142、47、-47、-142、-237、-332,最后根据返回的 8 位二进制数分析计算得出偏离距离。因此我们能够估计距离线中心-33 到+33 mm 的机器人位置。八个红外传感器依次连接 CPU 的 P7.7、P7.6、P7.5、P7.4、P7.3、P7.2、P7.1、P7.0 的八个 GPIO 口。
循迹模块传感器分布图
红外循迹模块接口图
4.1.2 碰撞转向
碰撞开关位于小车最前面,数量共计 6 个,连接小车的 P4 组引脚中的六个,当开关碰到障碍物时,被按下去,对应引脚会读出低电平,作为一个返回的信号。因此,实验中,我们通过上面的开关进行读电平来看是哪个开关碰到了障碍物,从而做出相应的转向动作。
6个防撞开关接口图
4.1.3 红外避障
该套件使用的为 3 个 Sharp DP2Y0A21YK0F 传感器,分别连接 CPU 的 P9.1、P9.0、P4.1 的三个 GPIO 口(图 2.13),探测范围 20cm-150cm,其输出电压与距离成反比。探测原理为三角测量原理:红外发射器以一定的角度发射红外光束,当遇到物体以后,光束会被反射回来。反射回来的红外光线被 CCD 检测器检测到以后,会获得一个偏移值 L,利用三角关系,在知道了发射角度 a,偏移距 L,中心矩 X,以及滤镜的焦距 f 以后,传感器到物体的距离 D 就可以通过几何关系计算出来了,从而判别是否进行避障改变前进方向。
红外测距模块接口图
测距传感器三角测量原理图
4.2 软件原理
4.2.1总体设计
根据设计要求,主要设计模块包括由红外循迹模块、防撞开关以及红外测距模块构成。
智能循迹小车需要沿着设定好的轨道前进,本设计的轨迹是在白色路面上铺设的黑色轨迹,于是就要求小车必须可以识别到白色路面上的黑色轨迹,这就需要红外循迹模块对路面进行不断的探测;同时,小车还应该可以实时检测是否偏离目标轨道并及时修正前进方向,这就需要传感器将检测到的路面信息实时反馈给微控制器,微控制器根据路面信息产生相对应的脉冲宽度调制信号(PWM波)传输到电机驱动电路,控制直流电机的转动的状态与速度,进行相应的左右转弯、前进后退,从而完成精确循迹。对于路面上的障碍物,小车还应该能够识别得到,对于远距离的障碍物,可以使用红外测距模块进行测距,在距离小于一定的范围时,进行相应的左右转弯或者后退;若是突然的出现障碍物则使用已经定义为中断的防撞开关来识别,进行相应的左右转弯或者后退。之后再继续循迹前进。总体的设计的框图如下:
总体的设计的框图
4.2.2 循迹
循迹模块的软件流程图如下,循迹模块的目的是让小车能够准确地识别到地面的黑线。小车在行驶过程中,若地面为白色,则接收管会接收到红外线信号,与之相对应的检测模块的 LED 的端口为高电平,小车会继续前进;若道路为黑色,接收端不会收到反馈的红外线信号,与之对应的检测模块的 LED 的端口为低电平,对应电机的转速会降低,小车两个电机之间会产生转速差,从而达到智能小车循迹的目的。智能小车循迹系统程序框图如下:
智能小车循迹系统程序框图
红外传感器具体的调试内容:
由8个传感器得到的8位二进制数来判断小车此刻的状态,从而让小车做出相应的调整,
若为0x18,则黑线位于小车中间,小车直行;
若为0x30,0x20,0x60,0x10,则黑线位于小车左侧,小车左转;
若为0x0c,0x01,0x02,0x04,0x08,则黑线位于小车右侧,小车右转;
若为0x0F,0x1F,则小车位于右转路口,小车先直行,再右转90度;
若为0xF0,0xF8,则小车位于左转路口,小车先直行,再左转90度;
若为0xFF,0x7F, 0xFE,0x7E,0x3F,0xFC,0x3C,0x7C,0x3E,则小车位于T型路口或者十字路口,小车先前进一小段距离,
若传感器的变为0x00,则是T型路口,直接左转或者右转90度;
若传感器的不是0x00,则是十字路口,继续前进;
若为0x00,则小车前方没有可循线路,小车掉头;其余的情况下就保持直行状态。
4.2.3 碰撞转向
在小车的前部放置6个碰撞传感器,并将它们与微处理器 MSP432 相连。碰撞传感器允许软件知道哪里与前方障碍物体相碰。根据小车操作手册可以得知MSP432 微处理器的 P4.7、P4.6、P4.5、P4.3、P4.2、P4.0 是从左到右6个碰撞传感器的GPIO口。将编写一个函数来初始化碰撞传感器 Bump_Init( )。该函数只需设置适当的端口引脚,并根据需要启用内部电阻。第二个函数 Bump_Read( ),读取开关并返回一个8位结果将碰撞开关的6为整合到第六位,高两位补零。为了简化小车的运动,我们将碰撞结果进行分类,6个传感器分成2组:左侧3个传感器 P4.7、P4.6、P4.5和右侧3个传感器P4.2、P4.0、P4.3。
在 uint8_t Bump_Read( )函数中,当左侧3个传感器发生碰撞时,返回值0x3b或者0x3d或者0x3e;当右侧3个传感器发生碰撞时,返回值0x1f或者0x2f或者0x37,并由返回值的大小在主程序中控制小车的运动。碰撞转向实现框图如下:
碰撞转向实现框图
4.2.4红外避障
红外避障使用夏普的 DP2Y0A21YK0F 红外距离传感器,将距离的物理信号转换为电压信号。但电压信号属于模拟信号,微处理器不能直接识别处理,此时需要利用 ADC 处理 IR 传感器输出的模拟信号。
模/数转换器(Analog to Digital Converter,简称 ADC)是电子设备中必备的重要器件,用于将模拟信号转变为微控制器可以识别的数字信号,包括:采样、保持、量化和编码 4 个过程。MSP432 包含一个 14 位的 ADC14 模块,支持快速14 位模/数转换。
ADC 的核心是将模拟输入转换为 14 位数字表示的数字信号,使用两个可编程电压(VR+和 VR-)来定义转换的上下限。
设n为 14 位 ADC 的采样值(从 0 到 16383),且 D 为距离,单位是 mm。二者之间存在如下的非线性转换关系:
D =1195172/(n -1058)
其中 1195172 和-1058 是校准系数的经验值,通过 ADC 实验取得的。得到准确的距离之后,我们就可以通过测量得到的距离值来判断小车的运行状态。,从而做出不同的反应,实现避障。红外避障实现框图如下:
红外避障实现框图
4.3软件实现
循迹、碰撞转向和红外避障这些功能的实现是在前两个实验的基础上,将碰撞开关配置为中断,对不同碰撞开关触发时做出不同的反应,配套的8路红外传感器对应的输入和输出管脚,调试在8路红外传感器的不同状态时,小车运行不同的状态,从而实现自动循迹;此外,将红外测距传感器获取的电信号转换为相应的距离,从而实现红外避障。
4.3.1.初始化
Clock_Init48MHz();//首先配置48MHz的时钟
Motor_Init();//初始化电机端,将P1.6,P1.7,P3.6, P3.7为输出端口,用于驱动电机
PWM_Init34(uint16_t period,uint16_t duty3,uint16_t duty4)//PWM初始化, 实现小车的电机驱动控制
ADC0_InitSWTriggerCh17_12_16();//初始化P9.0 A17 右边测距;P9.1 A16 左边测距;P4.1 A12 中间测距
ADC_In17_12_16(&ch1,&ch2,&ch3); //对ADC14模块进行初始化
uint32_t distance1; //左侧红外测距测得的距离
uint32_t distance2; //中间红外测距测得的距离
uint32_t distance3; //右侧红外测距测得的距离
uint32_t statue;/用于寄存P1.1和P1.4的值
uint32_t flag=0;// 根据P1.1和P1.4的值进行累加,来控制红外避障模块的开启和关闭
LaunchPad_Init();//初始化P1.1和P1.4输入开关,P2.2-P2.0输出
BumpInt_Init(&HandleCollision);//初始化碰撞开关配置为中断,并且引入处理碰撞的任务函数
在中断函数中,会调用处理碰撞的任务函数
CollisionFlag=0;//碰撞标志
4.3.2.运行主要函数
xunxian();//自动寻线函数
void xunxian(void)
{
Data = Reflectance_Read(500);
switch(Data){
case 0x18: //直行
Motor_Forward(L,R);
break;
case 0x30:
case 0x20:
case 0x60:
case 0x10: //机器人向右偏移了,需要向左转
Motor_Left(4000,3000);
Clock_Delay1ms(1);
break;
case 0x0c:
case 0x01:
case 0x02:
case 0x04:
case 0x08: //机器人向左偏移了,需要向右转
Motor_Right(3000,4000);
Clock_Delay1ms(1);
break;//Dismiss
case 0x0F:
Motor_Forward(L,R);
Clock_Delay1ms(350);
Motor_Right(L,R+1000);
Clock_Delay1ms(550); //右转90度
break;
//左转路口 、直行+右转路口
case 0x1F:
Motor_Forward(L,R);
Clock_Delay1ms(350);
Motor_Right(L,R+1000);
Clock_Delay1ms(550); //右转90度
break;
case 0xF0:
Motor_Forward(L,R);
Clock_Delay1ms(350);
Motor_Left(L+1000,R);
Clock_Delay1ms(550);
break;
//左转路口、 直行+左转路口
case 0xF8:
Motor_Forward(L,R);
Clock_Delay1ms(350);
Motor_Left(L+1000,R);
Clock_Delay1ms(550);
break;
case 0x00: //掉头
Motor_Left(L,R);
Clock_Delay1ms(1100); //450
break;
case 0xFF: // T 型路口 十字路口
case 0x7F:
case 0xFE:
case 0x7E:
case 0x3F:
case 0xFC:
case 0x3C:
case 0x7C:
case 0x3E:
Motor_Forward(L,R);
Clock_Delay1ms(150);
Data = Reflectance_Read(500);
if(Data != 0x00)
{
Motor_Forward(L,R);
}
else
{
Motor_Left(L+1000,R);
Clock_Delay1ms(550);
}
break;
default:
Motor_Forward(L,R);
break;
}
}
计算红外传感器的左、中、右3个距离:
distance1=z/(ch1-e);
distance2=z/(ch2-e);
distance3=z/(ch3-e);
获取按键引脚P1.1和P1.4的值来控制红外避障的开启与关闭:
statue=LaunchPad_Input();
while(LaunchPad_Input()!=0x00){};
if(statue!=0x00)flag++;
在首先判断是否开启红外避障模块,若不开启则直行,若开启,则在依次判断左、中、右三个位置的红外避障传感器的距离,若小于150mm,则往没有障碍的方向转弯,其中左侧的优先级最高
//LED 灯
#include "msp.h"
#include<stdio.h>
#include"../inc/Clock.h"
//LED 灯共阴极,给高电平亮灯
#define RED 0x01 //R
#define GREEN 0x02 //G
#define BLUE 0x04 //B
#define yellow RG- 0x03 //R+G
#define skyblue -GB 0x06 //G+B
#define white RGB 0x07 //R+G+B
#define pink R-B 0x05 //R+B
#define SW1 0x02 // on the left side of the LaunchPad board
#define SW2 0x10 // on the right side of the LaunchPad board
void Port1_Init(void){ //系统初始化,设置 IO 口属性
P1->SEL0 &= ~0x13; //选中P1.4 and P1.1作为 I/O 功能
P1->SEL1 &= ~0x13; // configure P1.4 and P1.1 as GPIO
P1->DIR = 0x01; // make P1.4 and P1.1 in, P1.0 output
P1->REN = 0x12; // enable pull resistors on P1.4 and P1.1
P1->OUT = 0x12;// P1.4 and P1.1 are pull-up 使能上拉/下拉电阻高电平有效
}
uint8_t Port1_Input(void){
return (P1->IN&0x12); // read P1.4,P1.1 inputs
}
void Port2_Init(void){
P2->SEL0 &= ~0x07;
P2->SEL1 &= ~0x07; //configure P2.2-P2.0 as GPIO
P2->DS = 0x07; // make P2.2-P2.0 high drive strength
P2->DIR = 0x07; //make P2.2-P2.0 out
P2->OUT= 0x00; //all LEDs off 输出初始为 0 灯灭
}
void Port2_Output(uint8_t data){
P2->OUT = data; // write all of P2 outputs
}
void main(void)
{
Clock_Init48MHz();
Port1_Init(); // initialize P1.1 and P1.4 and make them inputs
Port2_Init(); // initialize P2.2-P2.0 and make them outputs
uint8_t status; // uint8_t 是用 1 个字节表示的 相当于一个 char;输出 uint8_t类型的变量实际上输出对应的字符,而不是数值
uint8_t num=0x00;
uint8_t status1=0x01;
while(1){
status = Port1_Input();
while(Port1_Input()==0x10||Port1_Input()==0x02){}; //消抖
if((status&0x02)==0x00) //P1.1控制LED闪烁的颜色
status1=status1+0x01;
if((status&0x10)==0x00) //P1.4 控制LED控制闪烁
num=num+0x01;
if((status1&0x0F)==0x08)
status1=0x01;
switch(num%3){ // switches are negative logic on P1.1 and P1.4
case 0: // SW1 pressed
Port2_Output(status1);
break;
case 1: // SW1 pressed
Port2_Output(status1);
Clock_Delay1ms(500);
Port2_Output(0x00);
// Port1_Output(1);
Clock_Delay1ms(500);
break;
case 2: // SW2 pressed
Port2_Output(status1);
Clock_Delay1ms(25);
Port2_Output(0x00);
// Port1_Output(1);
Clock_Delay1ms(25);
break;
}
}
}
//电机驱动
#include "msp.h"
#include "../inc/Clock.h"
#include "../inc/Motor.h"
#include"../inc/CortexM.c"
//#include "gpio.h"
//#include "driverlib.h"
static uint8_t num2=0; //P1.4控制车速
static uint8_t num3=0; //P1.1控制方向
uint8_t b;
uint8_t c;
/**
* main.c
*/
void EdgeTrigger_Init(void){
P1->SEL0 &= ~0x12;
P1->SEL1 &= ~0x12; // configure P1.4 and P1.1 as GPIO
P1->DIR &= ~0x12; // make P1.4 input Button 2
P1->REN |= 0x12; // enable pull resistors
P1->OUT |= 0x12; // P1.4 pull-up*/
P1->IES |= 0x12; // P1.4 and P1.1 falling edge event
P1->IFG &= ~0x12; // clear flag4
P1->IE |= 0x12; // arm interrupt on P1.4 and P1.1
NVIC->IP[8]=(NVIC->IP[8]&0x00FFFFFF)|0x40000000;
NVIC->ISER[1] = 0x00000008; // enable
EnableInterrupts();
}
void PORT1_IRQHandler(void){ //中断服务函数
if((P1->IFG&0x12)==0x10) // clear flag4
{
P1->IFG &= ~0x12; // clear flag4
num2=num2+1;
}
else if((P1->IFG&0x12)==0x02)
{
P1->IFG &= ~0x12; // clear flag4
num3=num3+1;
}
else if((P1->IFG&0x12)==0x12)
{
P1->IFG &= ~0x12; // clear flag4
b=0;
c=0;
Motor_Stop();
}
}
uint8_t Port1_Input(void){
return (P1->IN&0x12); // read P1.4,P1.1 inputs
}
void main(void)
{
Clock_Init48MHz();
Motor_Init(); //初始化中电机
EdgeTrigger_Init(); //初始化中断
while(1){
//uint8_t status;
int right;
int left;
/*if((status&0x10)==0x00)
num2=num2+1;
else if((status&0x02)==0x00)
num3=num3+1;*/
while(Port1_Input()!=0x12){};
b=num2%4;
c=num3%5;
if(b==0)
{
right=4000;
left=4000;
}
else if(b==1)
{
right=8000;
left=8000;
}
else if(b==2)
{
right=12000;
left=12000;
}
else if(b==3)
{
right=0;
left=0;
}
if(c==0)
Motor_Forward(left,right);
else if(c==1)
Motor_Backward(left,right);
else if(c==2)
Motor_Right(left,right);
else if(c==3)
Motor_Left(left,right);
else if(c==4)
Motor_Stop();
}
}
(3)循迹、红外避障、碰撞
#include <stdint.h>
#include "../inc/ADC14.h"
#include "msp.h"
#include "..\inc\BumpInt.h"
#include "..\inc\LaunchPad.h"
#include "..\inc\UART0.h"
#include "..\inc\CortexM.h"
#include "..\inc\Motor.h"
#include "..\inc\PWM.h"
#include "..\inc\Clock.h"
#include "..\inc\IRDistance.h"
#include "../inc/Reflectance.h"
uint8_t Data;
uint16_t L = 5000;
uint16_t R = 5000;
uint32_t CollisionData, CollisionFlag;
uint32_t ch1,ch2,ch3;
int32_t z=1195172;
int32_t e=1058;
uint8_t data,cnt_collision=0;
void HandleCollision(uint8_t bumpSensor){
Motor_Stop();
CollisionData = bumpSensor;
CollisionFlag = 1;
if(CollisionData == 0x1f || CollisionData == 0x2f || CollisionData == 0x37)
{
Motor_Backward(5000,5000);
Clock_Delay1ms(300);
Motor_Left(7000,7000);
Clock_Delay1ms(300);
Motor_Stop();
}
else if(CollisionData == 0x3b || CollisionData == 0x3d || CollisionData == 0x3e)
{
Motor_Backward(5000,5000);
Clock_Delay1ms(300);
Motor_Right(7000,7000);
Clock_Delay1ms(300);
Motor_Stop();
}
}
void xunxian(void)
{
Data = Reflectance_Read(500);
switch(Data){
case 0x18: //直行
Motor_Forward(L,R);
// Clock_Delay1ms(100);
break;
case 0x30:
case 0x20:
case 0x60:
case 0x10: //机器人向左偏移了,需要向右转
//Motor_Backward(L,R);
// Clock_Delay1ms(1);
Motor_Left(4000,3000);
Clock_Delay1ms(1);
break;
case 0x0c:
case 0x01:
case 0x02:
case 0x04:
case 0x08: //机器人向右偏移了,需要向左转
//Motor_Backward(L,R);
// Clock_Delay1ms(1);
Motor_Right(3000,4000);
Clock_Delay1ms(1);
break;//Dismiss
case 0x0F:
Motor_Forward(L,R);
Clock_Delay1ms(350);
Motor_Right(L,R+1000);
Clock_Delay1ms(550); //左转90度
break;
case 0x1F:
Motor_Forward(L,R);
Clock_Delay1ms(350);
Motor_Right(L,R+1000);
Clock_Delay1ms(550); //左转90度
break;
// case 0x1E:
// Motor_Forward(L,R);
// Clock_Delay1ms(n);
// Motor_Left(L,R+1000);
// Clock_Delay1ms(450);
// break;
//左转路口 、直行+左转路口
case 0xF0:
Motor_Forward(L,R);
Clock_Delay1ms(350);
Motor_Left(L+1000,R);
Clock_Delay1ms(550);
break;
//右转路口、 直行+右转路口
case 0xF8:
Motor_Forward(L,R);
Clock_Delay1ms(350);
Motor_Left(L+1000,R);
Clock_Delay1ms(550);
break;
// case 0x78:
// Motor_Forward(L,R);
// Clock_Delay1ms(n);
// Motor_Right(L+1000,R);
// Clock_Delay1ms(450);
// break;
// case 0xD8:
// case 0x78:
// Motor_Forward(L,R);
// Clock_Delay1ms(600);
// Motor_Left(L,R+1000);
// Clock_Delay1ms(687);
// break;//Short Rectangle
// case 0x1E:
// case 0x1B:
// Motor_Forward(L,R);
// Clock_Delay1ms(600);
// Motor_Right(L+1000,R);
// Clock_Delay1ms(687);
// break;
//case 0xFF:
//case 0x7F:
//case 0xFE:
//case 0x3F:
//case 0xFC:
// Motor_Forward(L,R);
// break;
case 0x00: //掉头
Motor_Left(L,R);
Clock_Delay1ms(1100); //450
break;
case 0xFF: // T 型路口 十字路口
case 0x7F:
case 0xFE:
case 0x7E:
case 0x3F:
case 0xFC:
case 0x3C:
case 0x7C:
case 0x3E:
// Port2_Output(0x01);
Motor_Forward(L,R);
Clock_Delay1ms(150);
Data = Reflectance_Read(500);
if(Data != 0x00)
{
Motor_Forward(L,R);
// Clock_Delay1ms(550); //左转90度
}
else
{
Motor_Left(L+1000,R);
Clock_Delay1ms(550);
}
break;
default:
//Motor_Stop();
Motor_Forward(L,R);
break;
}
}
uint8_t Port1_Input(void){
return (P1->IN&0x12); //read P1.1 1.4 input
}
void Port2_Init(void){
P2->SEL0 = 0x00;
P2->SEL1 = 0x00; // configure P2.2-P2.0 as GPIO
P2->DS = 0x07; // make P2.2-P2.0 high drive strength
P2->DIR = 0x07; // make P2.2-P2.0 out
P2->OUT = 0x00; // all LEDs off
}
void Port2_Output(uint8_t data){ // write all of P2 outputs
P2->OUT = data;
}
void main(void){
Clock_Init48MHz();
Motor_Init();
ADC0_InitSWTriggerCh17_12_16();
uint32_t distance1;
uint32_t distance2;
uint32_t distance3;
uint32_t flag=0;
uint32_t statue;
UART0_Initprintf();
CollisionFlag=0;
LaunchPad_Init();
BumpInt_Init(&HandleCollision);
LaunchPad_LED(0);
while (1)
{
xunxian();
ADC_In17_12_16(&ch1,&ch2,&ch3);//对ADC14模块进行初始化
distance1=z/(ch1-e);
distance2=z/(ch2-e);
distance3=z/(ch3-e);
statue=LaunchPad_Input();
while(LaunchPad_Input()!=0x00){};
if(statue!=0x00)flag++;
if(flag%2==0){
if(distance1!=0&&distance1<150)
{
Motor_Left(6000,6000);
Clock_Delay1ms(500);
Motor_Stop();
}
else if(distance2!=0&&distance2<150)
{
Motor_Backward(6000,6000);
Clock_Delay1ms(500);
Motor_Right(6000,6000);
Clock_Delay1ms(100);
Motor_Stop();
}
else if(distance3!=0&&distance3<150)
{
Motor_Right(6000,6000);
Clock_Delay1ms(500);
Motor_Stop();
}
else
Motor_Forward(6000,6000);
}
else
{
Motor_Forward(6000,6000);
}
}
}
文章来源:https://www.toymoban.com/news/detail-520883.html
到了这里,关于智能循迹防碰撞小车的文章就介绍完了。如果您还想了解更多内容,请在右上角搜索TOY模板网以前的文章或继续浏览下面的相关文章,希望大家以后多多支持TOY模板网!