本项目通过TT扩展模块的GPIO功能,设置IO26为输入模式(下拉状态)外接人体红外传感器模块,设置监听IO口电平变化,当上升沿时触发中断处理函数,中断处理函数只做简单的状态和变量标记,在loop主循环中根据标记的变量和状态进行相应的反馈
代码
#include <RMTT_Libs.h>
#include <Wire.h>
RMTT_Protocol tt_sdk;
RMTT_RGB tt_rgb;
struct Button {
const uint8_t PIN;
uint32_t numberKeyPresses;
bool pressed;
};
Button button1 = {26, 0, false};
void IRAM_ATTR isr() {
button1.numberKeyPresses += 1;
button1.pressed = true;
tt_rgb.SetRGB(255, 255, 255);
}
void setup() {
Serial.begin(115200);
Serial1.begin(1000000, SERIAL_8N1, 23, 18);
pinMode(button1.PIN, INPUT_PULLUP);
attachInterrupt(button1.PIN, isr, RISING);
tt_rgb.Init();
tt_rgb.SetRGB(255, 0, 0);
tt_sdk.startUntilControl();
tt_sdk.sendTelloCtrlMsg("takeoff");
tt_rgb.SetRGB(0, 255, 0);
delay(10000);
tt_sdk.sendTelloCtrlMsg("land");
tt_rgb.SetRGB(0, 255, 0);
}
void loop() {
if (button1.pressed) {
button1.pressed = false;
tt_rgb.SetRGB(255, 0, 0);
}
delay(3000);
}
代码说明,中断函数在TT飞行中或降落后都可以正常触发,中断触发后RGB灯变白色,loop主循环监测到中断状态变化后设置RGB灯变绿色,周而复始从而展现中断的效果
评论