回到首页 返回首页
回到顶部 回到顶部
返回上一页 返回上一页

课时四:综合项目1--遥控无人机(队伍:PlutoCharon) 简单

头像 宫冰玉 2020.12.28 589 0

一、课程引入

(1)什么是传感器及其应用

(2)IR kit红外遥控介绍

(3)通过数字红外信号发射模块学习红外通讯

(4)Gravity:PAJ7620U2 手势识别传感器介绍

(5)电路实现

(6)自行通过编程实现通讯协议的分发

(7)如何调用官方库

一、知识原理讲解

2.1什么是传感器及其应用

传感器是一种检测装置,能感受到被测量的信息,并能将感受到的信息,按一定规律变换成为电信号或其他所需形式的信息输出,以满足信息的传输、处理、存储、显示、记录和控制等要求。

传感器的应用及其广泛,常见的手机上就集成了众多的传感器,如陀螺仪,用于检测手机的运动;红外传感器,可控制红外设备;摄像头,用于采集图像等。

2.2 IR kit红外遥控介绍

project-image

2.2.1红外接收头

红外遥控器发出的信号是一连串的二进制脉冲码 为了使其在无线传输过程中免受其他红外信号的干扰,通常都是先将其调制在特定的载波频率上,然后再经红外发射二极管发射出去,而红外线接收装置则要滤除其他杂波,只接收该特定频率的信号并将其还原成二进制脉冲码,也就是解调.

2.2.2工作原理

内置接收管将红外发射管发射出来的光信号转换为微弱的电信号,此信号经由IC内部放大器进行放大,然后通过自动增益控制、带通滤波、解调变、波形整形后还原为遥控器发射出的原始编码,经由接收头的信号输出脚输入到电器上的编码识别电路

2.2.3红外接收器引脚与连线

project-image

D为数据输出

GND为电源地

VCC为电源正

2.3通过数字红外信号发射模块学习红外通讯

要想对某一遥控器进行解码必须要了解该遥控器的编码方式,这就叫知己知彼,百战不殆 。本产品使用的遥控器的编码方式为:NEC协议。下面就介绍一下NEC协议:

NEC协议介绍:

特点: (1)8位地址位,8位命令位

(2)为了可靠性地址位和命令位被传输两次

(3)脉冲位置调制

(4)载波频率38khz

(5)每一位的时间为1.125ms或2.25ms

逻辑0和1的定义如下图:

project-image

协议如下:

按键按下立刻松开的发射脉冲:

project-image

上面的图片显示了NEC的协议典型的脉冲序列。注意:这是首先发送LSB(最低位)的协议。在上面的脉冲传输的地址为0x59命令为0x16。一个消息是由一个9ms的高电平开始,随后有一个4.5ms的低电平, (这两段电平组成引导码)然后由地址码和命令码。地址和命令传输两次。第二次所有位都取反,可用于对所收到的消息中的确认使用。总传输时间是恒定的,因为每一点与它取反长度重复。如果你不感兴趣, 你可以忽略这个可靠性取反,也可以扩大地址和命令,以每16位!

按键按下一段时间才松开的发射脉冲:

project-image

一个命令发送一次,即使在遥控器上的按键仍然按下。当按键一直按下时,第一个110ms的脉冲与上图一样,之后每110ms重复代码传输一次。这个重复代码是由一个9ms的高电平脉冲和一个2.25ms低电平和560μs的高电平组成。

重复脉冲:

project-image

注意:脉冲波形进入一体化接收头以后,因为一体化接收头里要进行解码、信号放大和整形,故要注意在没有红外信号时,其输出端为高电平,有信号时为低电平,故其输出信号电平正好和发射端相反。接收端脉冲大家可以通过示波器看到,结合看到的波形理解程序。

根据NEC编码的特点和接收端的波形,本实验将接收端的波形分成四部分:引导码(9ms和4.5ms的脉冲)、地址码16位(包括8位的地址位和8位的地址的取反)、命令码16位(包括8位命令位和8位命令位的取反)、重复码(9ms、2.25ms、560us脉冲组成)。 利用定时器对接收到的波形的高电平段和低电平段进行测量,根据测量到的时间来区分:逻辑“0”、逻辑“1”、引导脉冲、重复脉冲。引导码和地址码只要判断是正确的脉冲即可,不用存储,但是命令码必须存储,因为每个按键的命令码都不同, 根据命令码来执行相应的动作。设置遥控器上的几个按键VOL+:控制LED灯亮的;VOL-:作为控制蜂鸣器响;

遥控器键值附表(arduino):

project-image

2.4 Gravity:PAJ7620U2 手势识别传感器介绍

project-image

SEN0315手势识别传感器是一款强大的3D手势识别交互式传感器;在最远20cm范围内,最多可以识别13种手势。具备良好的手势识别稳定性和节能机制,总是能够在恰当的时候偷偷帮你节省电源;采用Gravity接口,零件的连接就不再是一件麻烦的事。目前有两种工作模式:高速模式下可以识别手的上\下\左\右\前\后\顺时针\逆时针移动以及快速挥动9种手势;低速模式下可以此前9种基础上再加乱序\缓慢左右\缓慢前后\缓慢上下移动4种手势。

高速模式:

注:顺时针和逆时针手势需要至少转两圈以上

project-image

低速模式:

低速模式下默认采样时间为2s,所以完成一项操作后可能需等待1s

project-image

2.4.1电路实现

project-image
project-image
project-image
project-image

三、项目实施步骤

(操作无人机时,请飞手请远离高速旋转的桨叶)

项目5:红外无线遥控控制无人机

项目描述:

该项目需要使用到IR kit红外遥控套件,并需要自行搭建电路与无人机连接,自行编写控制无人机的代码,下载编译,通过红外遥控器发出的遥控信号,实现自己想要的效果,例如:控制无人机上升、下降、左侧移、右侧移、一键起飞和一键降落、一键翻滚等

任务拆解:

任务流程图:

project-image

学生能力基础:

(1)IR kit红外遥控原理

(2)通信知识

(3)编程思想

材料清单

  • RoboMaster TT无人机 X1 链接
  • IR kit红外遥控套件 X1 链接

演示视频:

代码
#include <Arduino.h>
#include <RMTT_Libs.h>
#include <RMTT_Protocol.h>
#include <Wire.h>
#include <stdio.h>
#include <string.h>

#include "FS.h"
#include "SPIFFS.h"

#include <DFRobot_IRremote.h>

 // #define __UART0_DEBUG__

#ifdef __UART0_DEBUG__
#define CommonSerial Serial
#else
#define CommonSerial Serial1
#endif

#define FLIGHT      "1FE20DF"
#define DOWN        "1FE48B7"

#define YAW_LEFT    "1FE58A7"
#define YAW_RIGHT   "1FEA05F"
#define HIGHT_UP    "1FEC03F"
#define HIGHT_DOWN  "1FE807F"

#define VY_LEFT    "1FED827"
#define VY_RIGHT   "1FEF00F"
#define VX_UP      "1FE708F"
#define VY_DOWN    "1FE30CF"

#define ZERO        "1FE7887"


RMTT_RGB tt_rgb;
RMTT_Protocol tt_sdk;

// 动态变量
String mind_s_CMD;
volatile float mind_n_yaw, mind_n_hight, mind_n_vx, mind_n_vy;
// 创建对象
IRremote_Receive remoteReceive_26;

void WaitTelloReady();

TaskHandle_t userTaskHandle = NULL;
void user_task(void* arg);

void setup()
{
    Serial.begin(115200);
    Wire.begin(27, 26);
    Wire.setClock(400000);
    Serial1.begin(1000000, 23, 18, SERIAL_8N1);
    Serial.println();

    remoteReceive_26.begin(26);

    RMTT_RGB::Init();

    RMTT_RGB::SetRGB(255, 0, 0);
    tt_sdk.SDKOn();
    WaitTelloReady();
    /* 阻塞线程并一直读取无人机串口返回数据,此后Tello可以确保已经初始化完毕 */
    RMTT_RGB::SetRGB(0, 255, 255);

    /* Create tasks for multi-tasking  */
    /* Larger number represents higher priority  */

    xTaskCreateUniversal(user_task, "user_task", 8192, NULL, 1, &userTaskHandle, 1);
}

void user_task(void* arg)
{
    int Flag = 0;
    while (1)
    {
        /* Put your code here ! */
        mind_s_CMD = (remoteReceive_26.getIrCommand());
        if ((mind_s_CMD == String(FLIGHT))) {
            Flag = 0;
            RMTT_RGB::SetGreen(255);
            tt_sdk.TakeOff();

        }
        if ((mind_s_CMD == String(DOWN))) {
            Flag = 0;
            RMTT_RGB::SetGreen(0);
            tt_sdk.Land();
        }

        if ((mind_s_CMD == String(YAW_LEFT))) {
            Flag = 1;
            mind_n_yaw += 1;
            tt_sdk.sendTelloCtrlMsg((char*)String(String("ccw ") + int(2)).c_str());
        }
        if ((mind_s_CMD == String(YAW_RIGHT))) {
            Flag = 1;
            mind_n_yaw -= 1;
            tt_sdk.sendTelloCtrlMsg((char*)String(String("cw ") + int(2)).c_str());
        }
        if ((mind_s_CMD == String(HIGHT_UP))) {
            Flag = 1;
            mind_n_hight += 1;
            tt_sdk.sendTelloCtrlMsg((char*)String(String("up ") + int(20)).c_str());
        }
        if ((mind_s_CMD == String(HIGHT_DOWN))) {
            Flag = 1;
            mind_n_hight -= 1;
            tt_sdk.sendTelloCtrlMsg((char*)String(String("down ") + int(20)).c_str());
        }

        if ((mind_s_CMD == String(VY_LEFT))) {
            Flag = 1;
            mind_n_vy += 1;
            tt_sdk.sendTelloCtrlMsg((char*)String(String("left ") + int(20)).c_str());
        }
        if ((mind_s_CMD == String(VY_RIGHT))) {
            Flag = 1;
            mind_n_vy -= 1;
            tt_sdk.sendTelloCtrlMsg((char*)String(String("right ") + int(20)).c_str());
        }
        if ((mind_s_CMD == String(VX_UP))) {
            Flag = 1;
            mind_n_vx += 1;
            tt_sdk.sendTelloCtrlMsg((char*)String(String("forward ") + int(20)).c_str());
        }
        if ((mind_s_CMD == String(VY_DOWN))) {
            Flag = 1;
            mind_n_vx -= 1;
            tt_sdk.sendTelloCtrlMsg((char*)String(String("back ") + int(20)).c_str());
        }

        if ((mind_s_CMD == String(ZERO))) {
            Flag = 1;
            mind_n_yaw = 0;
            mind_n_hight = 0;
            mind_n_vx = 0;
            mind_n_vy = 0;
        }
        //if (Flag)
        //{
        //   tt_sdk.SetRC(mind_n_yaw, -mind_n_hight, -mind_n_vy, mind_n_vx);
        //}
        delay(10);
    }
}

void loop()
{
    /* Serial receive process from drone */
    pinMode(34, INPUT_PULLUP);
    // 等待按键被按下
    while (digitalRead(34) == 1);
    /* -------!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-------  */
    /* DO NOT ADD ANY CODE HERE FOR NOT BLOCKING THE RECEIVE FROM THE SERIAL */
    /*     YOU CAN ADD YOUR USER CODE TO THE 'user_task' FUNCTION ABOVE      */
    /* -------!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-------- */
}


void WaitTelloReady()
{
    while (1)
    {
        if (Serial1.available())
        {
            String ret = Serial1.readString();
            if (!strncmp(ret.c_str(), "ETT ok", 6))
            {
                Serial.println(ret.c_str());
                return;
            }
        }
        delay(500);
        tt_sdk.SDKOn();
    }
}

四、项目拓展

项目6:手势识别控制无人机

项目描述:

该项目需要使用到手势识别传感器和全彩灯带,并需要自行搭建电路,编写实现代码。最终通过手势动作控制无人机移动。

任务拆解:

任务流程图:

project-image

学生能力基础:

(1)Gravity:PAJ7620U2 手势识别传感器原理

(2)通信知识

(3)编程思想

材料清单

  • RoboMaster TT无人机 X1 链接
  • Gravity:PAJ7620U2 手势识别传感器 X1 链接

演示视频:

代码
#include <Arduino.h>
#include <RMTT_Libs.h>
#include <RMTT_Protocol.h>
#include <Wire.h>

#include <DFRobot_PAJ7620U2.h>

 // #define __UART0_DEBUG__

#ifdef __UART0_DEBUG__
#define CommonSerial Serial
#else
#define CommonSerial Serial1
#endif

// 创建对象
DFRobot_PAJ7620U2 paj;
RMTT_RGB tt_rgb;
RMTT_Protocol tt_sdk;



void WaitTelloReady();


TaskHandle_t userTaskHandle = NULL;
void user_task(void* arg);

void setup()
{
    Serial.begin(115200);
    Wire.begin(27, 26);
    Wire.setClock(400000);
    Serial1.begin(1000000, 23, 18, SERIAL_8N1);
    Serial.println();

    paj.begin();
    paj.setGestureHighRate(true);

    RMTT_RGB::Init();

    RMTT_RGB::SetRGB(255, 0, 0);
    tt_sdk.SDKOn();
    WaitTelloReady();
    /* 阻塞线程并一直读取无人机串口返回数据,此后Tello可以确保已经初始化完毕 */
    RMTT_RGB::SetRGB(0, 255, 255);

    /* Create tasks for multi-tasking  */
    /* Larger number represents higher priority  */

    xTaskCreateUniversal(user_task, "user_task", 8192, NULL, 1, &userTaskHandle, 1);
}

void user_task(void* arg)
{
    while (1)
    {
        /* Put your code here ! */

        DFRobot_PAJ7620U2::eGesture_t gesture = paj.getGesture();
        if (((paj.gestureDescription(gesture) == "Left"))) {
            tt_rgb.SetRGB(51, 255, 51);
            tt_sdk.sendTelloCtrlMsg((char*)String(String("right ") + int(50)).c_str());
        }
        if (((paj.gestureDescription(gesture) == "Right"))) {
            tt_rgb.SetRGB(255, 0, 0);
            tt_sdk.sendTelloCtrlMsg((char*)String(String("left ") + int(50)).c_str());
        }
        if (((paj.gestureDescription(gesture) == "Up"))) {
            tt_rgb.SetRGB(0, 0, 255);
            tt_sdk.TakeOff();
        }
        if (((paj.gestureDescription(gesture) == "Down"))) {
            tt_rgb.SetRGB(204, 51, 204);
            tt_sdk.Land();
        }
        delay(10);
    }
}

void loop()
{
    /* Serial receive process from drone */
    pinMode(34, INPUT_PULLUP);
    // 等待按键被按下
    while (digitalRead(34) == 1);
    /* -------!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-------  */
    /* DO NOT ADD ANY CODE HERE FOR NOT BLOCKING THE RECEIVE FROM THE SERIAL */
    /*     YOU CAN ADD YOUR USER CODE TO THE 'user_task' FUNCTION ABOVE      */
    /* -------!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-------- */
}


void WaitTelloReady()
{
    while (1)
    {
        if (Serial1.available())
        {
            String ret = Serial1.readString();
            if (!strncmp(ret.c_str(), "ETT ok", 6))
            {
                Serial.println(ret.c_str());
                return;
            }
        }
        delay(500);
        tt_sdk.SDKOn();
    }
}

评论

user-avatar