简介
GR10-30是一款支持12种手势的手势识别传感器,支持上、下、左、右、前、后、顺时针旋转、逆时针旋转、连续顺时针旋转、连续逆时针旋转、悬停、挥手手势识别,可以对手势的触发距离、旋转角度、悬停时间、识别窗口大小进行设置,使识别更加精准。GR10-30识别稳定,准确性高,最远识别距离可达30cm。同时,GR10-30有两个中断引脚用于指示有手势触发和有物体进入识别范围内。
GR10-30适用于无接触操作应用,可用于手势遥控器、机器人交互、人机界面控制、灯光控制、手势游戏机等应用。
特性
- 最远识别距离30cm
- 可识别12种手势
- 识别阈值参数可配置
- 支持UART、I2C通讯
应用场景
- 手势遥控器
- 机器人交互
- 人机界面控制
技术规格
- 供电电压:3.3V~5V
- 工作电流:10<mA
- I2C地址:0x73
- 波特率:9600
- 最远识别距离:30cm
- 工作温度范围:0℃~70℃
- 工作湿度范围:5%RH~85%RH
- 产品尺寸:20.5*23.5mm
引脚说明
序号 | 丝印 | 功能描述 |
---|---|---|
1 | VCC | 电源正极 |
2 | GND | 电源负极 |
3 | SCL | I2C时钟线 |
4 | SDA | I2C数据线 |
5 | RST | 复位引脚 |
6 | INT2 | 物体运动检测 当检测范围内有物体运动输出高电平,若无物体输出低电平,当物体静止或检范围被完全遮挡超过3S,同样会输出低电平 |
7 | INT1 | 手势识别中断 当识别到手势产生脉冲(10ms) |
8 | TX | 串口发送 |
9 | RX | 串口接收 |
Arduino使用教程
准备
- 硬件
- 1 x Arduino UNO控制板
- 1 x Fermion: GR10-30手势识别传感器
- 若干 杜邦线
- 软件
- Arduino IDE, 点击下载Arduino IDE
- RTU库(使用串口通讯时请安装RTU库)
- GR10-30库文件和示例程序
关于如何安装库文件,点击链接
接线图
样例代码1 - 轮询读取手势
通过轮询的方式读取手势
参数解释
-
gr10_30.setLeftRange(5);
当检测手向左移动五个单位后,判定为“向左”手势 -
移动距离(cm)=(手离传感器距离 * 设置参数)/25
-
gr10_30.setUdlrWin(18, 11);
设置识别区域为18*11单位面积 -
gr10_30.setCwsAngle(4);
当旋转90°后,判定为“旋转手势” -
旋转手势的识别距离为最远识别距离的一半左右
/*!
* @file getGestures.ino
* @brief 运行本例程读取手势的类型
* @n
* @n connected table
* ---------------------------------------------------------------------------------------------------------------
* board | MCU | Leonardo/Mega2560/M0 | UNO | ESP8266 | ESP32 | microbit |
* VCC | 3.3V/5V | VCC | VCC | VCC | VCC | X |
* GND | GND | GND | GND | GND | GND | X |
* RX | TX | Serial1 TX1 | 5 | 5/D6 | D2 | X |
* TX | RX | Serial1 RX1 | 4 | 4/D7 | D3 | X |
* ---------------------------------------------------------------------------------------------------------------
*
* @copyright Copyright (c) 2021 DFRobot Co.Ltd (http://www.dfrobot.com)
* @license The MIT License (MIT)
* @author [zhixinliu](zhixinliu@dfrobot.com)
* @version V0.1
* @date 2022-07-25
* @url https://github.com/DFRobor/DFRobot_GR10_30
*/
#include "DFRobot_GR10_30.h"
#if defined(ARDUINO_AVR_UNO)||defined(ESP8266)
#include <SoftwareSerial.h>
#endif
//#define UARTMODE // 串口模式
#define I2CMODE // i2c模式
#if defined UARTMODE
#if defined(ARDUINO_AVR_UNO)||defined(ESP8266)
SoftwareSerial mySerial(/*rx =*/4, /*tx =*/5);
DFRobot_GR10_30 gr10_30(/*addr =*/GR10_30_DEVICE_ADDR, /*s =*/&mySerial);
#else
DFRobot_GR10_30 gr10_30(/*addr =*/GR10_30_DEVICE_ADDR, /*s =*/&Serial1);
#endif
#endif
#if defined I2CMODE
DFRobot_GR10_30 gr10_30(/*addr = */GR10_30_DEVICE_ADDR, /*pWire = */&Wire);
#endif
void setup()
{
#if defined UARTMODE
//Init MCU communication serial port
#if defined(ARDUINO_AVR_UNO)||defined(ESP8266)
mySerial.begin(9600);
#elif defined(ESP32)
Serial1.begin(9600, SERIAL_8N1, /*rx =*/D3, /*tx =*/D2);
#else
Serial1.begin(9600);
#endif
#endif
Serial.begin(115200);
while(gr10_30.begin() != 0){
Serial.println(" Sensor initialize failed!!");
delay(1000);
}
Serial.println(" Sensor initialize success!!");
/** 设置需要启用的手势
* GESTURE_UP
* GESTURE_DOWN
* GESTURE_LEFT
* GESTURE_RIGHT
* GESTURE_FORWARD
* GESTURE_BACKWARD
* GESTURE_CLOCKWISE
* GESTURE_COUNTERCLOCKWISE
* GESTURE_WAVE It is not suggested to enable rotation gesture (CW/CCW) and wave gesture at the same time.
* GESTURE_HOVER Disable other gestures when hover gesture enables.
* GESTURE_UNKNOWN
* GESTURE_CLOCKWISE_C
* GESTURE_COUNTERCLOCKWISE_C
*/
gr10_30.enGestures(GESTURE_UP|GESTURE_DOWN|GESTURE_LEFT|GESTURE_RIGHT|GESTURE_FORWARD|GESTURE_BACKWARD|GESTURE_CLOCKWISE|GESTURE_COUNTERCLOCKWISE|GESTURE_CLOCKWISE_C|GESTURE_COUNTERCLOCKWISE_C);
// 开启后使用更加详细的配置,不开启使用默认的配置
/**
* 设置感兴趣的窗口,只在此范围内能采集的数据有效
* 窗口最大为31 配置的的数字代表 中心距离上下左右的距离
* 例如 配置上下的距离为30 中心距离上的距离为 15 距离下的范围也为15
* udSize 上下的距离范围 0-31
* lrSize 左右的距离范围 0-31
*/
// gr10_30.setUdlrWin(30, 30);
// gr10_30.setHovrWin(20, 20);
/**
* 设置滑动多少距离才能识别为手势
* 距离范围5-25, 必须小于感兴趣窗口的距离
*/
// gr10_30.setLeftRange(10);
// gr10_30.setRightRange(10);
// gr10_30.setUpRange(10);
// gr10_30.setDownRange(10);
// gr10_30.setForwardRange(10);
// gr10_30.setBackwardRange(10);
/**
* 设置前后移动多少距离才能识别为手势
* 距离范围 1-15
*/
// gr10_30.setForwardRange(10);
// gr10_30.setBackwardRange(10);
/**
* 设置挥手多少次才能识别
* 次数范围 1-15
*/
// gr10_30.setWaveNumber(2);
/**
* 设置悬停多少时间才能触发手势
* 1-200 10ms-2s 默认为60 600ms
*/
// gr10_30.setHovrTimer(60);
/**
* 设置旋转多少角度才能触发手势
* count 默认为 16 范围 0-31
* count 旋转的度数为22.5 * count
* count = 16 22.5*count = 360 旋转360度触发手势
*/
// gr10_30.setCwsAngle(/*count*/16);
// gr10_30.setCcwAngle(/*count*/16);
/**
* 设置连续旋转多少角度才能触发手势
* count 默认为 4 范围 0-31
* count 连续旋转的度数为22.5 * count
* 例: count = 4 22.5*count = 90
* 先触发顺/逆时针旋转手势, 当还继续旋转时, 每90度触发一次连续旋转手势
*/
// gr10_30.setCwsAngleCount(/*count*/8);
// gr10_30.setCcwAngleCount(/*count*/8);
}
void loop()
{
if(gr10_30.getDataReady()){
uint16_t gestures = gr10_30.getGesturesState();
if(gestures&GESTURE_UP){
Serial.println("Up");
}
if(gestures&GESTURE_DOWN){
Serial.println("Down");
}
if(gestures&GESTURE_LEFT){
Serial.println("Left");
}
if(gestures&GESTURE_RIGHT){
Serial.println("Right");
}
if(gestures&GESTURE_FORWARD){
Serial.println("Forward");
}
if(gestures&GESTURE_BACKWARD){
Serial.println("Backward");
}
if(gestures&GESTURE_CLOCKWISE){
Serial.println("Clockwise");
}
if(gestures&GESTURE_COUNTERCLOCKWISE){
Serial.println("Contrarotate");
}
if(gestures&GESTURE_WAVE){
Serial.println("Wave");
}
if(gestures&GESTURE_HOVER){
Serial.println("Hover");
}
if(gestures&GESTURE_CLOCKWISE_C){
Serial.println("Continuous clockwise");
}
if(gestures&GESTURE_COUNTERCLOCKWISE_C){
Serial.println("Continuous counterclockwise");
}
}
delay(1);
}
结果
样例代码2 - 中断读取手势
通过中断的方式读取手势
/*!
* @file softGetData.ino
* @brief 运行本例程可以使用中断读取手势
* @n
* @n connected table
* ---------------------------------------------------------------------------------------------------------------
* board | MCU | Leonardo/Mega2560/M0 | UNO | ESP8266 | ESP32 | microbit |
* VCC | 3.3V/5V | VCC | VCC | VCC | VCC | X |
* GND | GND | GND | GND | GND | GND | X |
* RX | TX | Serial1 TX1 | 5 | 5/D6 | D2 | X |
* TX | RX | Serial1 RX1 | 4 | 4/D7 | D3 | X |
* ---------------------------------------------------------------------------------------------------------------
*
* @copyright Copyright (c) 2021 DFRobot Co.Ltd (http://www.dfrobot.com)
* @license The MIT License (MIT)
* @author [zhixinliu](zhixinliu@dfrobot.com)
* @version V0.1
* @date 2022-07-25
* @url https://github.com/DFRobor/DFRobot_GR10_30
*/
#include "DFRobot_GR10_30.h"
#if defined(ARDUINO_AVR_UNO)||defined(ESP8266)
#include <SoftwareSerial.h>
#endif
//#define UARTMODE // 串口模式
#define I2CMODE // i2c模式
#if defined UARTMODE
#if defined(ARDUINO_AVR_UNO)||defined(ESP8266)
SoftwareSerial mySerial(/*rx =*/4, /*tx =*/5);
DFRobot_GR10_30 gr10_30(/*addr =*/GR10_30_DEVICE_ADDR, /*s =*/&mySerial);
#else
DFRobot_GR10_30 gr10_30(/*addr =*/GR10_30_DEVICE_ADDR, /*s =*/&Serial1);
#endif
#endif
#if defined I2CMODE
DFRobot_GR10_30 gr10_30(/*addr = */GR10_30_DEVICE_ADDR, /*pWire = */&Wire);
#endif
volatile uint8_t interruptFlag = 0;
void myInterrupt(void)
{
interruptFlag = 1; // Interrupt flag
#if defined(ESP32) || defined(ESP8266) || defined(ARDUINO_SAM_ZERO)
detachInterrupt(13); // Detach interrupt
#else
detachInterrupt(0); // Detach interrupt
#endif
}
void setup()
{
#if defined UARTMODE
//Init MCU communication serial port
#if defined(ARDUINO_AVR_UNO)||defined(ESP8266)
mySerial.begin(9600);
#elif defined(ESP32)
Serial1.begin(9600, SERIAL_8N1, /*rx =*/D3, /*tx =*/D2);
#else
Serial1.begin(9600);
#endif
#endif
Serial.begin(115200);
while(gr10_30.begin() != 0){
Serial.println(" Sensor initialize failed!!");
delay(1000);
}
Serial.println(" Sensor initialize success!!");
/** 设置需要启用的手势
* GESTURE_UP
* GESTURE_DOWN
* GESTURE_LEFT
* GESTURE_RIGHT
* GESTURE_FORWARD
* GESTURE_BACKWARD
* GESTURE_CLOCKWISE
* GESTURE_COUNTERCLOCKWISE
* GESTURE_WAVE It is not suggested to enable rotation gesture (CW/CCW) and wave gesture at the same time.
* GESTURE_HOVER Disable other gestures when hover gesture enables.
* GESTURE_UNKNOWN
* GESTURE_CLOCKWISE_C
* GESTURE_COUNTERCLOCKWISE_C
*/
gr10_30.enGestures(GESTURE_UP|GESTURE_DOWN|GESTURE_LEFT|GESTURE_RIGHT|GESTURE_FORWARD|GESTURE_BACKWARD|GESTURE_CLOCKWISE|GESTURE_COUNTERCLOCKWISE|GESTURE_CLOCKWISE_C|GESTURE_COUNTERCLOCKWISE_C);
// 开启后使用更加详细的配置,不开启使用默认的配置
/**
* 设置感兴趣的窗口,只在此范围内能采集的数据有效
* 窗口最大为31 配置的的数字代表 中心距离上下左右的距离
* 例如 配置上下的距离为30 中心距离上的距离为 15 距离下的范围也为15
* udSize 上下的距离 距离范围 0-31
* lrSize 左右的距离 距离范围 0-31
*/
// gr10_30.setUdlrWin(30, 30);
// gr10_30.setHovrWin(20, 20);
/**
* 设置滑动多少距离才能识别为手势
* 距离范围 5-25, 必须小于感兴趣窗口的距离
*/
// gr10_30.setLeftRange(10);
// gr10_30.setRightRange(10);
// gr10_30.setUpRange(10);
// gr10_30.setDownRange(10);
// gr10_30.setForwardRange(10);
// gr10_30.setBackwardRange(10);
/**
* 设置前后移动多少距离才能识别为手势
* 距离范围 1-15
*/
// gr10_30.setForwardRange(10);
// gr10_30.setBackwardRange(10);
/**
* 设置挥手多少次才能识别
* 次数范围 1-15
*/
// gr10_30.setWaveNumber(2);
/**
* 设置悬停多少时间才能触发手势
* 1 - 200 10ms-2s 默认为60 600ms
*/
// gr10_30.setHovrTimer(60);
/**
* 设置旋转多少角度才能触发手势
* count 默认为 16 范围1-31
* count 旋转的度数为22.5 * count
* count = 16 22.5*count = 360 旋转360度触发手势
*/
// gr10_30.setCwsAngle(/*count*/16);
// gr10_30.setCcwAngle(/*count*/16);
/**
* 设置连续旋转多少角度才能触发手势
* count 默认为 4 范围1-31
* count 连续旋转的度数为22.5 * count
* 例: count = 4 22.5*count = 90
* 先触发顺/逆时针旋转手势, 当还继续旋转时, 每90度触发一次连续旋转手势
*/
// gr10_30.setCwsAngleCount(/*count*/8);
// gr10_30.setCcwAngleCount(/*count*/8);
// 连接开发板的中断引脚
#if defined(ESP32) || defined(ESP8266)
/**!
Select according to the set DADY pin polarity
INPUT_PULLUP // Low polarity, set pin 13 to pull-up input
INPUT_PULLDOWN // High polarity, set pin 13 to pull-down input
interput io
All pins can be used. Pin 13 is recommended
*/
pinMode(/*Pin */13 ,INPUT_PULLUP);
attachInterrupt(/*interput io*/13, myInterrupt, ONLOW);
#elif defined(ARDUINO_SAM_ZERO)
pinMode(/*Pin */13 ,INPUT_PULLUP);
attachInterrupt(/*interput io*/13, myInterrupt, LOW);
#else
/**! The Correspondence Table of AVR Series Arduino Interrupt Pins And Terminal Numbers
* ---------------------------------------------------------------------------------------
* | | Pin | 2 | 3 | |
* | Uno, Nano, Mini, other 328-based |--------------------------------------------|
* | | Interrupt No | 0 | 1 | |
* |-------------------------------------------------------------------------------------|
* | | Pin | 2 | 3 | 21 | 20 | 19 | 18 |
* | Mega2560 |--------------------------------------------|
* | | Interrupt No | 0 | 1 | 2 | 3 | 4 | 5 |
* |-------------------------------------------------------------------------------------|
* | | Pin | 3 | 2 | 0 | 1 | 7 | |
* | Leonardo, other 32u4-based |--------------------------------------------|
* | | Interrupt No | 0 | 1 | 2 | 3 | 4 | |
* |--------------------------------------------------------------------------------------
*/
/**! The Correspondence Table of micro:bit Interrupt Pins And Terminal Numbers
* ---------------------------------------------------------------------------------------------------------------------------------------------
* | micro:bit | DigitalPin |P0-P20 can be used as an external interrupt |
* | (When using as an external interrupt, |---------------------------------------------------------------------------------------------|
* |no need to set it to input mode with pinMode)|Interrupt No|Interrupt number is a pin digital value, such as P0 interrupt number 0, P1 is 1 |
* |-------------------------------------------------------------------------------------------------------------------------------------------|
*/
/**!
Select according to the set DADY pin polarity
INPUT_PULLUP // Low polarity, set pin 2 to pull-up input
*/
pinMode(/*Pin */2 ,INPUT_PULLUP);
/**!
Set the pin to interrupt mode
// Open the external interrupt 0, connect INT1/2 to the digital pin of the main control:
function
callback function
state
LOW // When the pin is at low level, the interrupt occur, enter interrupt function
*/
attachInterrupt(/*Interrupt No*/0, /*function*/myInterrupt ,/*state*/LOW );
#endif
}
void loop()
{
/**!
When the interrupt occur in DRDY IO, get the geomagnetic data (get the data ready status through hardware)
Enable interrupt again
*/
if(interruptFlag == 1){
uint16_t gestures = gr10_30.getGesturesState();
if(gestures&GESTURE_UP){
Serial.println("Up");
}
if(gestures&GESTURE_DOWN){
Serial.println("Down");
}
if(gestures&GESTURE_LEFT){
Serial.println("Left");
}
if(gestures&GESTURE_RIGHT){
Serial.println("Right");
}
if(gestures&GESTURE_FORWARD){
Serial.println("Forward");
}
if(gestures&GESTURE_BACKWARD){
Serial.println("Backward");
}
if(gestures&GESTURE_CLOCKWISE){
Serial.println("Clockwise");
}
if(gestures&GESTURE_COUNTERCLOCKWISE){
Serial.println("Contrarotate");
}
if(gestures&GESTURE_WAVE){
Serial.println("Wave");
}
if(gestures&GESTURE_HOVER){
Serial.println("Hover");
}
if(gestures&GESTURE_CLOCKWISE_C){
Serial.println("Continuous clockwise");
}
if(gestures&GESTURE_COUNTERCLOCKWISE_C){
Serial.println("Continuous counterclockwise");
}
interruptFlag = 0;
#if defined(ESP32) || defined(ESP8266)
attachInterrupt(13, myInterrupt, ONLOW);
#elif defined(ARDUINO_SAM_ZERO)
attachInterrupt(13, myInterrupt, LOW);
#else
attachInterrupt(0, myInterrupt, LOW);
#endif
}
delay(1);
}
结果
主要API接口函数列表
/**
* @fn enGestures
* @brief 启用手势
* @param gestures
* GESTURE_UP
* GESTURE_DOWN
* GESTURE_LEFT
* GESTURE_RIGHT
* GESTURE_FORWARD
* GESTURE_BACKWARD
* GESTURE_CLOCKWISE
* GESTURE_COUNTERCLOCKWISE
* GESTURE_WAVE It is not suggested to enable rotation gesture (CW/CCW) and wave gesture at the same time.
* GESTURE_HOVER Disable other gestures when hover gesture enables.
* GESTURE_UNKNOWN
* GESTURE_CLOCKWISE_C
* GESTURE_COUNTERCLOCKWISE_C
* @return NONE
*/
void enGestures(uint16_t gestures);
/**
* @fn getExist
* @brief 获取物体是否在传感器检测范围内
* @return 是否存在
* @retval 1 存在
* @retval 0 不存在
*/
uint16_t getExist(void);
/**
* @fn getDataReady
* @brief 获取是否检测到手势了
* @return 是否检测到手势
* @retval 1 检测到手势
* @retval 0 未检测到手势
*/
uint16_t getDataReady(void);
/**
* @fn getGesturesState
* @brief 获取手势类型
* @return 手势类型
* @retval GESTURE_UP
* @retval GESTURE_DOWN
* @retval GESTURE_DOWN
* @retval GESTURE_LEFT
* @retval GESTURE_RIGHT
* @retval GESTURE_FORWARD
* @retval GESTURE_BACKWARD
* @retval GESTURE_CLOCKWISE
* @retval GESTURE_COUNTERCLOCKWISE
* @retval GESTURE_WAVE
* @retval GESTURE_HOVER
* @retval GESTURE_UNKNOWN
* @retval GESTURE_CLOCKWISE_C
* @retval GESTURE_COUNTERCLOCKWISE_C
*/
uint16_t getGesturesState(void);
/**
* @fn setUdlrWin
* @brief 设置上下左右感兴趣的窗口
* @param udSize 上下的距离 距离范围 0-31
* @param lrSize 左右的距离 距离范围 0-31
* @return NONE
*/
void setUdlrWin(uint8_t udSize, uint8_t lrSize);
/**
* @fn setLeftRange
* @brief 设置向左滑动多少距离才能识别
* @param range
* @n 距离范围 0-31,必须小于感兴趣的左右距离
* @return NONE
*/
void setLeftRange(uint8_t range);
/**
* @fn setRightRange
* @brief 设置向右滑动多少距离才能识别
* @param range
* @n 距离范围 0-31,必须小于感兴趣的左右距离
* @return NONE
*/
void setRightRange(uint8_t range);
/**
* @fn setUpRange
* @brief 设置向上滑动多少距离才能识别
* @param range
* @n 距离范围 0-31,必须小于感兴趣的上下距离
* @return NONE
*/
void setUpRange(uint8_t range);
/**
* @fn setDownRange
* @brief 设置向下滑动多少距离才能识别
* @param range
* @n 距离范围 0-31,必须小于感兴趣的上下距离
* @return NONE
*/
void setDownRange(uint8_t range);
/**
* @fn setForwardRange
* @brief 设置向前移动多少距离才能识别
* @param range
* @n 距离范围 0-31
* @return NONE
*/
void setForwardRange(uint8_t range);
/**
* @fn setBackwardRange
* @brief 设置向后移动多少距离才能识别
* @param range
* @n 距离范围 0-31
* @return NONE
*/
void setBackwardRange(uint8_t range);
/**
* @fn setWaveNumber
* @brief 设置挥手多少次才能识别
* @param number
* @n 次数范围 0-15
* @return NONE
*/
void setWaveNumber(uint8_t number);
/**
* @fn setHovrWin
* @brief 设置悬停感兴趣的窗口
* @param udSize 上下的距离 距离范围 0-31
* @param lrSize 左右的距离 距离范围 0-31
* @return NONE
*/
void setHovrWin(uint8_t udSize, uint8_t lrSize);
/**
* @fn setHovrTimer
* @brief 设置悬停多少时间才能触发手势
* @param timer
* @n timer 1-0x3ff 10ms-10s 默认为0X3c 600ms
* @return NONE
*/
void setHovrTimer(uint16_t timer);
/**
* @fn setCwsAngle
* @brief 设置顺时针旋转多少角度才能触发手势
* @param count 默认为 16 范围1-31
* @n count 旋转的度数为22.5 * count
* @n 例: count = 16 22.5*count = 360 旋转360度触发手势
* @return NONE
*/
void setCwsAngle(uint8_t count);
/**
* @fn setCcwAngle
* @brief 设置逆时针旋转多少角度才能触发手势
* @param count 默认为 16 范围1-31
* @n count 旋转的度数为22.5 * count
* @n 例: count = 16 22.5*count = 360 旋转360度触发手势
* @return NONE
*/
void setCcwAngle(uint8_t count);
/**
* @fn setCwsAngleCount
* @brief 设置顺时针连续旋转多少角度才能触发手势
* @param count 默认为 4 范围1-31
* @n count 连续旋转的度数为22.5 * count
* @n 例: count = 4 22.5*count = 90
* @n 先触发顺/逆时针旋转手势, 当还继续旋转时, 每90度触发一次连续旋转手势
* @return NONE
*/
void setCwsAngleCount(uint8_t count);
/**
* @fn setCcwAngleCount
* @brief 设置逆时针连续旋转多少角度才能触发手势
* @param count 默认为 4 范围1-31
* @n count 连续旋转的度数为22.5 * count
* @n 例: count = 4 22.5*count = 90
* @n 先触发顺/逆时针旋转手势, 当还继续旋转时, 每90度触发一次连续旋转手势
* @return NONE
*/
void setCcwAngleCount(uint8_t count);
树莓派使用教程
准备
-
硬件
- 树莓派4代B型(或类似)主控板 x 1
- Fermion: GR10-30手势识别传感器 x 1
- 若干杜邦线 x 1
-
软件
接线图
- 将模块与树莓派按照连线图相连。
安装驱动
-
启动树莓派的I2C接口。如已开启,可跳过该步骤。
打开终端(Terminal),键入如下指令,并回车:
pi@raspberrypi:~ $ sudo raspi-config
然后用上下键选择“ 5 Interfacing Options ”, 按回车进入,选择 “ P5 I2C ”, 按回车确认“ YES ”即可。重启树莓派主控板。 -
安装Python依赖库与git,树莓派需要联网。如已安装,可跳过该步骤。
在终端中,依次键入如下指令,并回车:
pi@raspberrypi:~ $ sudo apt-get update
pi@raspberrypi:~ $ sudo apt-get install build-essential python-dev python-smbus git
-
下载DFRobot_GR10_30驱动库。在终端中,依次键入如下指令,并回车:
pi@raspberrypi:~ $ cd Desktop/
pi@raspberrypi:~/Desktop $ git clone https://github.com/DFRobot/DFRobot_GR10_30
注意:
样例代码
样例代码1-轮询获取手势(get_getures.py)
- 在终端中,键入如下指令并回车,运行样例代码:
pi@raspberrypi:~/Desktop $ cd DFRobot_GR10_30/python/raspberry/example/
pi@raspberrypi:~/Desktop/DFRobot_GR10_30/python/raspberry/example/ $ python get_getures.py
样例代码2-中断获取手势(interrupt_get_getures.py)
- 在终端中,键入如下指令并回车,运行样例代码:
pi@raspberrypi:~/Desktop $ cd DFRobot_GR10_30/python/raspberry/example/
pi@raspberrypi:~/Desktop/DFRobot_GR10_30/python/raspberry/example/ $ python interrupt_get_getures.py
Modbus RTU协议
注:通讯接口使用UART
SEN0543 GR10-30 寄存器表(V1.0).xlsx
常见问题
还没有客户对此产品有任何问题,欢迎通过qq或者论坛联系我们!
更多问题及有趣的应用,可以 访问论坛 进行查阅或发帖。