第1部分


这篇文章来源于DevicePlus.com英语网站的翻译稿。
image10-2.jpg
试想一下,您刚搬到一个新地方,需要尽快添置家具,但是手头没有卷尺可以进行测量。那么,这款Parallax激光Arduino机器人就会派上用场!

在本文中,我们将让机器人能够动起来并且添加激光测距(LRF)功能,以使该设备能够检测物体并测量距离。
激光传感器会帮我们获得更准确、更可靠的数据。该Arduino机器人的移动方式为自主移动模式。它在移动的过程中能够检测到障碍物并主动避开。
该机器人的设计目标如下:

  • 向前、向后移动;向左和向右旋转90度;向左和向右旋转45度。
  • 基于最佳路径,通过向不同方向移动避开障碍物。
  • 测量各个方向(前方、左右90度、左右45度)的距离。
  • 基于可用的最长距离,确定朝哪个方向前进(向前、向后、向左或向右)。
传感器安装在伺服上,以便机器人可以左右平移以进行多次测量。测量的距离将显示在一块小型OLED显示屏上。我们将使用步进电机实现平稳、安静的运行。
我们会一步一步地讨论该Arduino机器人的构建过程。第一步是如何安装底盘、电机和Arduino/电机开发板。然后,我们利用一个小程序来测试电机,以确保系统连接和软件安装都准确无误。然后,我们会逐步添加其余设备,并且每一步都通过程序来测试安装和连接是否正确。通过这种按部就班的方法能够让我们更方便地解决制作过程中遇到的任何问题。

硬件

制作该机器人所需的硬件请参见以下硬件明细,这些零部件在许多电商处都可以买到(明细中给出了部分地址)。


    • Arduino Uno rev 3 (www.adafruit.com/products/50)
    • 适用于Arduino的Adafruit步进电机开发套件 (www.adafruit.com/products/1438)
    • 步进电机(www.adafruit.com/products/324)
    • 底盘、螺丝和尾轮  Parallax.com
    • 车轮、橡胶轮胎和轮毂  Makeblock.com
    • 伺服装置和安装套件(www.parallax.com/product/570-28015)
    • Parallax激光测距仪(www.parallax.com/product/28044)
    • OLED显示屏(www.seeedstudio.com/Grove-OLED-Display-1.12”-p-824.html)
    • 红色包装纸/盒(https://www.seeedstudio.com/Grove-Red-Wrapper-1*2(4-PCS-pack)-p-2585.html
    • 锂聚合物电池3型(11.1V)和连接器(https://www.hobbyking.com/hobbyking/store/__18203)
    • 195 x 195 x 3mm亚克力板(https://www.jaycar.com.au/clear-acrylic-sheet/p/HM9509)

软件

  • Arduino IDE
  • Adafruit Motor Shield Library https://learn.adafruit.com/adafruit-motor-shield-v2-for-arduino/install-software
  • LCD Display9696 Library.zip https://wiki.seeedstudio.com/File:LCD_Display9696_Library.zip
工具

  • 圆锉
  • Dremel 电动工具
  • 电烙铁
  • 迷你钢锯

安装电机、轮子和亚克力底座

Parallax底盘由高强度铝制成。该部件是专门为伺服系统而不是步进电机设计的,因此我们需要做一些修改。
首先,要将电机安装到机箱上,我们得在机箱的两侧开口。请用Dremel电动工具按照电机的安装尺寸精确切割机箱。
我们使用的步进电机型号为NEMA 17,其分辨率为200步/转。其供电规格为12V 350mA。
要将电机装入底盘内,我们需要尺寸为6.5cm x 4.5cm的亚克力板,如图1所示。请用钢锯将亚克力板切割成所需尺寸,然后用Dremel电动工具钻孔。用M2x10mm的螺钉将电机装在亚克力安装板上,两个电机需要8颗螺钉。然后,将制作完毕的亚克力板和电机安装到底盘内。
image01-3.jpg
图1.将步进电机安装在6.5×4.5cm亚克力板上

要固定Arduino和OLED显示屏,我们需要切割一块15cmx8cm的亚克力底座(图2)。请用4个垫片和螺丝安装亚克力底座,然后用附带的销钉安装尾轮。
image09-2.jpg
图2.机箱、尾轮和15×8亚克力板底座
image07-2.jpg
图3.轮子和轴连接器
image06-2.jpg
图4.安装在底盘上的步进电机和尾轮

我们需要用图3中所示的轴连接器安装轮子。但是,我们必须做一个小修改。轴孔的直径为4mm,而步进电机轴的直径为5mm。因此,我们需要将连接器的孔扩大到5mm。请使用圆锉或Dremel工具扩孔。扩孔时一定要小心操作!
image02-3.jpg
图5.安装在底盘上的亚克力底座

请将电机线缆从顶部的孔穿出,然后用双面胶带将电池粘在机箱下方。对于该项目来说,锂聚合物电池是理想解决方案。其供电规格为11.1V 800mAh〜1000mAh,这使得系统续航可超过1小时,而且还可以充电。但是该电池需要专门的充电器。如果您是航空模型或遥控车爱好者,那么您肯定知道这种电池。我们也可以用6或8节AA电池(9-12V)代替。
image08-2.jpg
图6.用双面胶将电池粘在底盘上

将电机电缆连至电机开发板

Adafruit 电机开发板规格 – Adafruit

  • 与Arduino高分辨率专用计时器相连的两个5V Hobby伺服器接口
  • 4个H桥:搭载TB6612芯片组,每个桥可提供1.2A电流(峰值为3A,持续20ms),具有热关断保护功能,以及内部反冲保护二极管。可为电机提供4.5VDC至13.5VDC供电。
  • 可连接最多4个双向直流电机,具有单独8位速度选择功能。
  • 可连接最多2个单线圈、双线圈、交叉步进或微步进电机(单极或双极)。
  • 经测试与Arduino UNO、Leonardo、ADK/Mega R3、Diecimila和Duemilanove兼容。兼容Due,配有3.3v逻辑跳线。兼容Mega/ADK R2及更早版本,具有2个跳线。
  • 5v3.3v逻辑电平(跳线可配置)。
该电机开发板能同时运行2个步进电机和2个伺服器。该步进电机开发板的一个很大优势在于它不占用任何Arduino引脚,因为它通过I2C连接。唯一需要引脚的是伺服器。我们只需按照说明连接电机电缆即可。
image00-2.jpg
图7.将电机连至电机开发板
image03-3.jpg
图8.亚克力底座上的Arduino和电机开发板

现在,我们只需要根据下图安装轮子和电池接头即可。
image05-2.jpg
图9.步进电机电缆连至电机开发板

安装软件并上传代码

现在,我们可以运行第一段代码了!首先,我们需要从Arduino网站下载并安装Arduino IDE,从Adafruit网站上下载并安装电机开发板库。安装成功后,请将以下源代码复制到Arduino中。
  • //*******************************************************************************************************************************************
  • #include <Wire.h>
  • #include <Adafruit_MotorShield.h>
  • #include "utility/Adafruit_MS_PWMServoDriver.h"
  • Adafruit_MotorShield AFMS = Adafruit_MotorShield();
  • Adafruit_StepperMotor *myMotor1 = AFMS.getStepper(200, 1);
  • Adafruit_StepperMotor *myMotor2 = AFMS.getStepper(200, 2);
  • void setup()
  • {  Serial.begin(9600);           // set up Serial library at 9600 bps
  • Serial.println("Stepper test!");
  • AFMS.begin();  // create with the default frequency 1.6KHz  
  • myMotor1->setSpeed(100);  // 100 rpm   
  • myMotor2->setSpeed(100);  // 100 rpm   
  • }
  • void loop()
  • {
  • Motor(50,3);                    // turn Left for 50 steps
  • delay(1000);
  • Motor(100,4);                   // turn Right for 100 steps
  • delay(1000);
  • Motor(50,3);                    // turn Left for 50 steps (back to original position)
  • delay(1000);
  • Motor(400,1);                   // move Forward for 400 steps
  • delay(1000);
  • Motor(400,2);                   // move Backward for 400 steps
  • delay(1000);
  • }
  • //******************************************* *************************************
  • void Motor(int x,int y)
  • {   int i = 0;
  • for ( i; (i < x); i ++)
  • { if (y == 1)   // move forward
  • { myMotor1->step(1, FORWARD, SINGLE);
  • myMotor2->step(1, BACKWARD, SINGLE);}
  •   if (y == 2)   // move backward
  • {myMotor1->step(1, BACKWARD, SINGLE);
  • myMotor2->step(1, FORWARD, SINGLE);}
  • if (y == 3)    // move left
  •   { myMotor1->step(1, FORWARD, SINGLE);
  • myMotor2->step(1, FORWARD, SINGLE);}
  • if (y == 4)    // move right
  •   { myMotor1->step(1, BACKWARD, SINGLE);
  • myMotor2->step(1, BACKWARD, SINGLE);}}
  • }
  • //********************************************************************************************************************************************
  • 复制代码
    这段代码非常简单。其目的是让机器人能够向左旋转90度以及向右旋转90度。该程序还能让机器人返回到起始位置:向前移动400步,然后向后移动回到起始位置。在程序循环中,我们运行Motor函数,该函数具有2个参数。第一个参数表明电机必须旋转多少步,第二个参数表明电机移动方向(向前、向后、向左和向右)。
    程序运行后,该Arduino机器人应该会像上述视频显示的那样移动。
    我们将继续添加其他系统部件,比如伺服器和激光测距仪(LRF),并编写一个程序,让机器人能够自主移动。


    第2部分
    image06-4.jpg
    在第1部分中,我们制作了一块定制的亚克力板底座,把NEMA 17步进电机安装到了底盘上。然后,我们将Arduino Uno 3和电机开发板也连到亚克力底座上,并安装了电机开发板库。在第2部分中,我们将添加机器人工作所需的其他系统部件,比如伺服器和激光测距仪(LRF),并编写一个程序,让机器人能够自主移动。
    在本文中,我们将进一步增加机器人的功能:让该机器人动起来并为其增加激光测距(LRF)功能,以使该设备能够检测物体并测量距离。
    该机器人的设计目标如下:

    • 向前、向后移动;向左和向右旋转90度;向左和向右旋转45度。
    • 避开障碍物时根据最佳可用路径朝不同的方向移动。
    • 测量各个方向(前方、左右90度、左右45度)的距离。
    • 根据可用的最长距离,确定朝哪个方向前进(向前、向后、向左或向右)。

    硬件
    制作此机器人所需的硬件请参见以下硬件明细,这些零部件在许多电商处都可以买到(明细中给出了部分地址)。



      • Arduino Uno rev 3 (www.adafruit.com/products/50)
      • 适用于Arduino的Adafruit步进电机开发套件(www.adafruit.com/products/1438)
      • 步进电机 (www.adafruit.com/products/324)
      • 底盘、螺丝和尾轮  Parallax.com
      • 车轮、橡胶轮胎和轮毂  Makeblock.com
      • 伺服装置和安装套件 (www.parallax.com/product/570-28015)
      • Parallax激光测距仪 (www.parallax.com/product/28044)
      • OLED显示屏 (www.seeedstudio.com/Grove-OLED-Display-1.12”-p-824.html)
      • 红色包装纸/盒 (https://www.seeedstudio.com/Grove-Red-Wrapper-1*2(4-PCS-pack)-p-2585.html
      • 锂聚合物电池3型(11.1V)和连接器 (https://www.hobbyking.com/hobbyking/store/__18203
      • 195 x 195 x 3mm亚克力板 (https://www.jaycar.com.au/clear-acrylic-sheet/p/HM9509)

    软件

    • Arduino IDE
    • Adafruit Motor Shield Library
    • LCD Display9696 Library.zip

    工具

    • 圆锉
    • Dremel 电动工具
    • 电烙铁
    • 迷你钢锯

    安装并测试伺服器

    下一步是安装用于平移的伺服器。首先,请用螺钉将两块小板拧到伺服基座上,然后用螺钉将其固定到亚克力底座上,如图1和图2所示。请用2个螺钉将铝制安装架安装到伺服器的顶部。
    image09-4.jpg
    图1.用两小板将伺服器固定到亚克力底座上
    image02-5.jpg
    图2.将铝制安装架安装到伺服器上

    如图3所示,将伺服器的接头连至电机开发板。电机开发板上有2个伺服器接头,分别标记为“servo1”和“servo2”。本次连接请使用servo1接头(外侧的那个)。请注意,切勿接反。
    image-04.jpg
    图3.伺服与电机开发板的连接

    现在,我们可以运行程序了,请将以下代码上传到Arduino。无需安装新库,系统所需的库(Servo.h)都已包含在Arduino IDE程序中。伺服器应使用Digital引脚10(servo 1),或者如果伺服器连接到电机开发板的servo 2,那么应使用引脚11。
  • //***********************************************************************************************
  • #include <Servo.h>
  • Servo panMotor;                      // servo for laser range finder (lrf) scanning
  • int pos = 0;    // variable to store the servo position
  • const int a = 1000;
  • void setup()
  • { panMotor.attach(10); }             // Attach Servo for scanning to pin 10
  • void loop()
  • {
  • // *************************** Scan Left ***********************************   
  •    panMotor.write(180);       // 90 degree
  •    delay(a);      
  •    panMotor.write(135);       // 45 degree
  •    delay(a);
  • // ************************** Scan Right  **********************************      
  •    panMotor.write(45);        // 45 degree
  •    delay(a);     
  •    panMotor.write(0);         // 90 degree
  •    delay(a);
  • // ************************* Neutral position *****************************   
  •    panMotor.write(90);
  •    delay(a);  
  • }
  • //**************************************************************************************************
  • 复制代码
    代码很简单,它负责让机器人从左向右进行扫描并返回原始位置。

    安装激光测距仪(LRF)

    激光测距仪产品文档– Parallax  
    https://www.parallax.com/download/

    Parallax激光测距仪(LRF)模块是一款利用激光技术计算仪器到目标物体的距离的测量仪器。该设备根据光学三角测量法(激光、摄像头和物体质心之间的简单三角函数)来计算仪器到目标物体的距离。其最佳测量范围为6–48英寸(15–122厘米),测量精度误差<5%(平均3%)。
    硬件安装很简单。只需在亚克力板上钻两个与LRF位置相匹配的孔,然后用塑料垫片和螺钉将LRF固定到铝底盘上即可(请参见图5)。
    image13-3-e1477704198167.jpg
    图4.将LRF电缆连至电机开发板
    image13-4.jpg
    图5.安装在铝制安装架上的LRF

    由于LRF的最佳测量值上限为122厘米,我们需要将铝制安装架稍微向前弯曲,以使该范围始终小于120厘米(图6)。
    image-08.jpg
    图6.向前弯曲铝制安装架,使激光到地的距离小于120厘米

    请完全按照图7将电缆接头连至LRF。GND接地,VCC接5V,SOUT接引脚8,SIN接引脚9。
    image07-4.jpg
    图7. LRF与电机开发板的连接

    我们已经完成了LRF的安装和连接,现在就来上传代码吧!同样,无需安装库。我们要用的SoftwareSerial.h已经包含在Arduino IDE中。
    下面的代码源自示例代码,我们只是进行了一些修改,将距离数据从字符串转换为整数。其作用是测量传感器到前方物体的距离并打印结果。我们用串行监视器显示结果。
  • // **************************************************************************************************************************************************
  • #include <SoftwareSerial.h>
  • #define rxPin     8                   // Serial input (connects to the LRF's SOUT pin)
  • #define txPin     9                   // Serial output (connects to the LRF's SIN pin)
  • #define ledPin   13                   // Most Arduino boards have an on-board LED on this pin
  • #define BUFSIZE  16                   // Size of buffer
  • int  lrfDataInt;
  • SoftwareSerial lrfSerial =  SoftwareSerial(rxPin, txPin);
  • void setup()                          // Set up code called once on start-up
  • {
  • // *************************************** setup for LRF ***********************************************
  • pinMode(ledPin, OUTPUT);
  • pinMode(rxPin, INPUT);
  • pinMode(txPin, OUTPUT);
  • digitalWrite(ledPin, LOW);                // turn LED off
  • Serial.begin(9600);
  • while (!Serial);                          // Wait until ready
  • Serial.println("\n\nParallax Laser Range Finder");
  • lrfSerial.begin(9600);
  • Serial.print("Waiting for the LRF...");
  • delay(2000);                             // Delay to let LRF module start up
  • lrfSerial.print('U');                    // Send character
  • while (lrfSerial.read() != ':');   
  • delay(10);                               // Short delay
  • lrfSerial.flush();                       // Flush the receive buffer
  • Serial.println("Ready!");
  • Serial.flush();                          // Wait for all bytes to be transmitted to the Serial Monitor
  • }
  • // ******************************************  main loop ************************************************
  • void loop()  // Main code, to run repeatedly
  • {
  • lrf();
  • }
  • // ****************************************** end main loop *********************************************
  • void lrf()
  • {
  • lrfSerial.print('R');                    // Send command
  • digitalWrite(ledPin, HIGH);              // Turn LED on while LRF is taking a measurement
  • char lrfData[BUFSIZE];                   // Buffer for incoming data
  • int  lrfDataInt1;
  • int  lrfDataInt2;
  • int  lrfDataInt3;
  • int  lrfDataInt4;
  • int offset = 0;                          // Offset into buffer
  • lrfData[0] = 0;                          // Clear the buffer   
  • while(1)
  • {
  •    if (lrfSerial.available() > 0)         // If there are any bytes available to read, then the LRF must have responded
  •    {
  •      lrfData[offset] = lrfSerial.read();  // Get the byte and store it in our buffer
  •      if (lrfData[offset] == ':')          // If a ":" character is received, all data has been sent and the LRF is ready to accept the next command
  •       { lrfData[offset] = 0;              // Null terminate the string of bytes we just received
  •        break; }                           // Break out of the loop
  •      offset++;                            // Increment offset into array
  •      if (offset >= BUFSIZE) offset = 0;   // If the incoming data string is longer than our buffer, wrap around to avoid going out-of-bounds
  •    }
  • }
  • lrfDataInt1 = ( lrfData[5] -'0');
  • lrfDataInt2 = ( lrfData[6] -'0');
  • lrfDataInt3 = ( lrfData[7] -'0');
  • lrfDataInt4 = ( lrfData[8] -'0');
  • lrfDataInt = (1000*lrfDataInt1)+ (100*lrfDataInt2)+(10*lrfDataInt3) + lrfDataInt4;
  • Serial.print("Distance = ");             // The lrfData string should now contain the data returned by the LRF, so display it on the Serial Monitor
  • Serial.println(lrfDataInt);
  • Serial.flush();                          // Wait for all bytes to be transmitted to the Serial Monitor
  • digitalWrite(ledPin, LOW);               // Turn LED off
  • delay(1000);
  • }
  • //*************************************************************************************************************************************************
  • 复制代码
    串行监视器显示的结果如下所示。所有尺寸的单位均为毫米
    image03-5.jpg

    安装OLED显示屏

    首先,我们将OLED塑料盒安装到亚克力底座中(请参见图9),然后再将OLED显示屏附带的线缆一端连至显示屏。要将显示屏连至电机开发板,请将线缆另外一端jst接头上的线缆剪下,然后将红导线焊至5V,将黑导线焊至Ground,将黄导线焊至SDA引脚,将绿导线焊至SCL引脚。请确保OLED显示屏的背面朝外。

    image08-4.jpg
    图8 . OLED与电机开发板之间的连接

    将OLED固定在底座上并连接电缆后,我们就可以运行部分软件了。

    首先,请确保已经安装了SeeedOLED.h。然后,将以下代码上传到Arduino。该代码使用了名为oled1的函数,稍后的最终编码也会使用该函数。其基本功能就是显示100到109的数字。
  • //*****************************************************************************************************************************************
  • #include <Wire.h>
  • #include <SeeedOLED.h>
  • int distanceFwd;
  • void setup()
  • { Wire.begin();}
  • void loop()
  • {
  • int i = 0;
  • for (i; (i < 10); i ++)
  • { distanceFwd = 100 + i;
  • oled1();
  • delay(1000); }
  • }
  •   void oled1()
  • {
  • SeeedOled.clearDisplay();           //clear the screen and set start position to top left corner
  • SeeedOled.setNormalDisplay();       //Set display to Normal mode
  • SeeedOled.setPageMode();            //Set addressing mode to Page Mode
  • SeeedOled.setTextXY(3,3);         
  • SeeedOled.putString("Forward :");
  • SeeedOled.setTextXY(5,9);
  • SeeedOled.putNumber(distanceFwd);
  • }  
  • //*****************************************************************************************************************************************
  • 复制代码
    程序正常运行时,显示屏应该会显示以下视频中的内容:

    安装最终代码
    现在,我们已经完成了所有硬件的安装并测试了各个设备。让我们把所有软硬件结合起来,构建一个可以自主移动的智能激光机器人吧。最终程序会执行以下功能:

    • 测量前方距离

      • 如果距离超过70厘米,机器人将向前移动500步(大约50厘米);
      • 如果距离大于40厘米小于70cm,机器人将向前移动200步(20厘米);
      • 如果距离小于40厘米,机器人会向左扫描90度,向左扫描45度,向右扫描45度,向右扫描90度;
    • 测量每个方向的距离,然后计算哪个方向的测量距离最长;
    • 转向距离最长的那个方向;
    • 返回第一步。

    请复制以下代码并将其上传到Arduino:
  • //*********************************************************************************************************************
  • #include <Wire.h>
  • #include <Adafruit_MotorShield.h>
  • #include "utility/Adafruit_MS_PWMServoDriver.h"
  • #include <SoftwareSerial.h>
  • #include <Servo.h>
  • #include <SeeedOLED.h>
  • #define ledPin   13                                         
  • #define BUFSIZE  16   
  • #define rxPin    8                                          // Serial input (connects to the LRF's SOUT pin)
  • #define txPin    9                                          // Serial output(connects to the LRF's SIN pin)
  • SoftwareSerial lrfSerial =  SoftwareSerial(rxPin, txPin);   // Size of buffer (in bytes) for incoming data
  • // Create the motor shield object with the default I2C address
  •   Adafruit_MotorShield AFMS = Adafruit_MotorShield();
  • // Connect a stepper motor with 200 steps per revolution (1.8 degree)
  •   Adafruit_StepperMotor *myMotor1 = AFMS.getStepper(200, 1);  // motor port #1 (M1 and M2)
  •   Adafruit_StepperMotor *myMotor2 = AFMS.getStepper(200, 2);  // motor port #2 (M3 and M4)
  •   Servo panMotor;                                             // servo for laser range finder (lrf) scanning
  •   int leftDistance1;
  •   int leftDistance2;
  •   int rightDistance1;
  •   int rightDistance2;
  •   int maxDistance;
  •   int angleTurn;
  •   int directions;
  •   int distanceFwd;  
  •   const int a = 30;                  
  • //*********************************************************************************start set up **************************
  • void setup() {
  • Serial.begin(9600);                                       // set up Serial library at 9600 bps
  • panMotor.attach(10);                                      // Attach Servo for scanning to pin 10
  • AFMS.begin();                                             // create with the default frequency 1.6KHz
  • myMotor1->setSpeed(100);                                  // Set stepmotor1 speed at 100 rpm   
  • myMotor2->setSpeed(100);                                  // Set stepmotor2 speed at 100 rpm   
  • pinMode(ledPin, OUTPUT);
  • pinMode(rxPin, INPUT);                                    // Input pin for LRF
  • pinMode(txPin, OUTPUT);                                   // Output pin for LRF
  • digitalWrite(ledPin, LOW);                                // turn LED off
  • Serial.begin(9600);
  • while (!Serial);                                          // Wait until ready
  • lrfSerial.begin(9600);
  • Serial.print("Waiting for the LRF...");
  • delay(2000);                                              // Delay to let LRF module start up
  • lrfSerial.print('U');                                     // Send character
  • while (lrfSerial.read() != ':');                        
  • delay(10);                                                // Short delay
  • lrfSerial.flush();                                        // Flush the receive buffer
  • Serial.println("Ready!");
  • Serial.flush();                                           // Wait for all bytes to be transmitted to the Serial Monitor
  • panMotor.write(90);
  • delay(a);
  • }
  • //******************************************************************* start Loop *****************************************
  • void loop()
  • {
  • distanceFwd = lrf();
  • maxDistance = distanceFwd;
  • oled1();
  • if (distanceFwd > 700)
  • { Motor(500,1);}
  • else
  • if (distanceFwd > 400)
  • { Motor(200,1);}
  • else                                                           // if path is blocked
  • { checkTurn();
  •   turn();}     
  • }
  • //***************************************************************** check turn  function ********************************
  • void checkTurn()
  • {
  •     digitalWrite(ledPin, HIGH);     
  • // ************************** Scan Left ***********************************   
  •    panMotor.write(180);
  •    delay(a);
  •    leftDistance1 = lrf();      
  •    
  •    panMotor.write(135);
  •    delay(a);
  •    leftDistance2 = lrf();
  •    oled();  
  •    
  • // *************************** Scan Right  *********************************      
  •    panMotor.write(45);
  •    delay(a);
  •    rightDistance2 = lrf();  
  •       
  •    panMotor.write(0);
  •    delay(a);
  •    rightDistance1 = lrf();
  •    oled();
  •    panMotor.write(90);
  •    
  •   digitalWrite(ledPin, LOW);
  • // ************************************ Turn Left ************************
  •      maxDistance = leftDistance1;
  •      angleTurn = 100;
  •      directions = 0;         
  • if (maxDistance <= leftDistance2)
  •     {angleTurn = 50;
  •      maxDistance = leftDistance2;
  •      directions = 0;
  •     }           
  • //*********************************** Turn Right ***********************            
  • if (maxDistance <= rightDistance2)
  •       {angleTurn = 50;
  •       maxDistance = rightDistance2;
  •       directions = 1;  
  •       }
  •       
  • if (maxDistance <= rightDistance1)
  •       {angleTurn = 100;
  •       maxDistance = rightDistance1;
  •       directions = 1;
  •       }                 
  • // ******************************* Turn Back******************************
  • if ((leftDistance1 < 300) && (rightDistance1 <300) && (distanceFwd <300))
  •    {angleTurn = 200;
  •    directions = 3;
  •    }                 
  • }
  •    
  • //************************************************ turn function *********************************************************
  • void turn()  
  • {
  •    rightDistance1 = 0;
  •    rightDistance2 = 0;
  •    leftDistance1  = 0;
  •    leftDistance2  = 0;
  •    
  •    if (directions == 0) // turn left  
  •     { Motor(angleTurn,3);}
  •    if (directions == 1) // turn right
  •     { Motor(angleTurn,4);}
  •    if (directions == 3) // turn back
  •     { Motor(angleTurn,4);}
  • }
  • //***************************************  Stepper Motor function    ****************************************************
  • void Motor(int x,int y)
  • {
  •   int i = 0;
  • for ( i; (i < x); i ++)
  • {
  •   if (y == 1)   // move forward
  • {myMotor1->step(1, FORWARD, SINGLE);
  • myMotor2->step(1, BACKWARD, SINGLE);}
  •   if (y == 2)   // move backward
  • {myMotor1->step(1, BACKWARD, SINGLE);
  • myMotor2->step(1, FORWARD, SINGLE);}
  • if (y == 3)    // move left
  •   { myMotor1->step(1, FORWARD, SINGLE);
  • myMotor2->step(1, FORWARD, SINGLE);}
  • if (y == 4)    // move right
  •   { myMotor1->step(1, BACKWARD, SINGLE);
  • myMotor2->step(1, BACKWARD, SINGLE);}
  • }
  • }
  • //***********************************************************************  LRF function *******************************
  • long lrf()
  • {
  • lrfSerial.print('R');         // Send command
  • digitalWrite(ledPin, HIGH);   // Turn LED on while LRF is taking a measurement
  • char lrfData[BUFSIZE];        // Buffer for incoming data
  • int  lrfDataInt1;
  • int  lrfDataInt2;
  • int  lrfDataInt3;
  • int  lrfDataInt4;
  • int  lrfDataInt;
  • int offset = 0;              // Offset into buffer
  • lrfData[0] = 0;              // Clear the buffer   
  • while(1)
  • {
  •    if (lrfSerial.available() > 0)
  •    {
  •      lrfData[offset] = lrfSerial.read();  
  •      if (lrfData[offset] == ':')        
  •       { lrfData[offset] = 0;
  •         break;}               
  •      offset++;
  •      if (offset >= BUFSIZE) offset = 0;
  •    }
  • }
  • lrfDataInt1 = ( lrfData[5] -'0');
  • lrfDataInt2 = ( lrfData[6] -'0');
  • lrfDataInt3 = ( lrfData[7] -'0');
  • lrfDataInt4 = ( lrfData[8] -'0');
  • lrfDataInt = (1000*lrfDataInt1)+ (100*lrfDataInt2)+(10*lrfDataInt3) + lrfDataInt4;     
  • Serial.flush();            
  • digitalWrite(ledPin, LOW);  
  • return lrfDataInt;
  • }
  • //********************************************************* Oled function ************************************************
  • void oled()
  • {
  • SeeedOled.clearDisplay();           //clear the screen and set start position to top left corner
  • SeeedOled.setNormalDisplay();       //Set display to Normal mode
  • SeeedOled.setPageMode();            //Set addressing mode to Page Mode
  • SeeedOled.setTextXY(0,0);         
  • SeeedOled.putString("Left 1:");
  • SeeedOled.setTextXY(0,12);
  • SeeedOled.putNumber(leftDistance1);   
  • SeeedOled.setTextXY(2,0);         
  • SeeedOled.putString("Left 2:");
  • SeeedOled.setTextXY(2,12);
  • SeeedOled.putNumber(leftDistance2);   
  • SeeedOled.setTextXY(4,0);         
  • SeeedOled.putString("Right 1:");
  • SeeedOled.setTextXY(4,12);
  • SeeedOled.putNumber(rightDistance1);
  • SeeedOled.setTextXY(6,0);         
  • SeeedOled.putString("Right 2:");
  • SeeedOled.setTextXY(6,12);
  • SeeedOled.putNumber(rightDistance2);      
  • }
  •    void oled1()
  • {
  • SeeedOled.clearDisplay();           //clear the screen and set start position to top left corner
  • SeeedOled.setNormalDisplay();       //Set display to Normal mode
  • SeeedOled.setPageMode();            //Set addressing mode to Page Mode
  • SeeedOled.setTextXY(3,3);         
  • SeeedOled.putString("Forward :");
  • SeeedOled.setTextXY(5,9);
  • SeeedOled.putNumber(distanceFwd);
  • }  
  • //***********************************************************************************************************************************
  • 复制代码
    image06-4.jpg
    图9. OLED显示屏安装在亚克力底座上的最终效果

    结论

    在本例中,凭借激光传感器,我们的机器人不仅能够检测并避开物体,同时还能获取更准确的距离数据。激光机器人还有许多其他应用场景。您也可以利用该激光传感器设计自己喜欢的有趣项目。

    来源:techclass.rohm