前一篇教程中,我们学习了利用Android手机的重力传感器来控制机械臂的运动,现在我们来学习利用ADXL_345三周加速度传感器通过手势来控制机械臂。其中的原理和Android手机控制差不多,只不过将安卓手机换成了ADXL_345模块。我们需要将ADXL_345模块获得的三轴加速度通过计算得到pitch和roll,然后通过ESP8266WiFi开发板将其发送到另一块ESP8266开发板来控制机械臂的运动。
ESP8266WiFi开发板x2
ADXL_345三轴传感器
迷你机械臂(SG90舵机)
按键开关一个
10KΩ电阻一个
面包板+若干跳线
电路接线如下图所示,机械臂的接线没有变化:
实物接线如下:
这里我们使用步进电机代替了底座的舵机,底座使用舵机注意将代码中的步进电机部分注释掉,并将注释的舵机部分取消注释。
这里我们将ADXL_345三轴加速度传感器连接的ESP8266当做客户端,另一块当做服务器端。 这里我们用到了ADXL_345的库:ADXL_345.zip(点击下载)
/**********************************************************
* 文件: Arm_client.ino by 零知实验室([url=http://www.lingzhilab.com]www.lingzhilab.com[/url])
* -^^- 零知开源,让电子制作变得更简单! -^^-
* 时间: 2019/06/17 12:32
* 说明:
************************************************************/
#include <ESP8266WiFi.h>
#include <ADXL345.h>
#define SSID "xxx" //要连接的wifi名字
#define PASSWD "xxx" //要连接的wifi密码
const uint16_t port = 8888;
const char * host = "192.168.0.131"; //服务器端的ip地址
WiFiClient client; //创建一个tcp client连接
ADXL345 accel;
float xg,yg,zg;
int pitch,roll;
int sign = 0;
// 复位或上电后运行一次:
void setup() {
//在这里加入初始化相关代码,只运行一次:
Serial.begin(9600);
Serial.println("Initializing I2C devices...");
accel.initialize();
Serial.println("Testing device connections...");
if(accel.testConnection()) //检测ADXL345是否连接
{
Serial.println("ADXL345 connection successful");
}else{
Serial.println("ADXL345 disconnection");
}
WiFi.mode(WIFI_STA);
WiFi.begin(SSID,PASSWD);
Serial.println("Wait for WiFi... ");
//等待wifi连接成功
while (WiFi.status() != WL_CONNECTED) {
Serial.print(".");
delay(500);
}
Serial.println("");
Serial.println("WiFi connected");
Serial.print("IP address: ");
Serial.println(WiFi.localIP());
while(!client.connect(host, port)) { //连接服务器
Serial.println("connection failed");
Serial.println("wait 5 second...");
delay(5000);
}
Serial.print("connecting to ");
Serial.println(host);
delay(500);
}
//一直循环执行:
void loop() {
// 在这里加入主要程序代码,重复执行:
if(sign == 0) //当sign为0时,执行以下代码
{
accel.readNormalize(&xg,&yg,&zg); //获取ADXL_345的加速度值
pitch = (atan2(xg,sqrt(yg*yg+zg*zg))*180)/M_PI; //计算pitch和roll
roll = (atan2(yg, zg)*180)/M_PI;
Serial.print("pitch=");
Serial.print(pitch);
Serial.print(" roll=");
Serial.println(roll);
client.println("("+String(pitch)+","+String(roll)+")"); //将pitch和roll以字符串的形式发送到服务器
sign = 1; //将pitch和roll发送至服务器后sign置1
}
sign = client.read(); //读取服务器端发送过来的信号
// Serial.println(sign);
}
这里我们需要将代码中的SSID和PASSWD改成你所需要连接的WiFi账号密码。
#define SSID "xxx" //要连接的wifi名字
#define PASSWD "xxx" //要连接的wifi密码
服务器端代码: 因为每个人组装完机械臂之后,舵机的可旋转角度范围都会不一向,所以以下部分代码的参数要根据实际情况来修改以下
pos2 = map(pitch,0,90,100,180); //后面两个参数100,180改成组装机械臂后舵机能旋转的角度范围
pos3 = map(roll,-90,90,0,180);
int pos = 110;
if(pos == 110) //这里的角度110,30也改成你组装成机械臂后舵机实际的旋转角度范围
{
for (pos; pos>30; pos--)
{
myservo.write(pos);
Serial.println(pos);
delay(20);
}
}
else if(pos == 30)
{
for (pos; pos<110; pos++)
{
myservo.write(pos);
Serial.println(pos);
delay(20);
}
}
以下是服务器端完整代码:
/**********************************************************
* 文件: Arm_server.ino by 零知实验室([url=http://www.lingzhilab.com]www.lingzhilab.com[/url])
* -^^- 零知开源,让电子制作变得更简单! -^^-
* 时间: 2019/06/17 14:12
* 说明:
************************************************************/
#include <ESP8266WiFi.h>
#include <Stepper.h>
#include <Servo.h>
//#define STEPS 256
#define key D8
#define port 8888 //端口号
WiFiServer server(port);
//Stepper stepper(STEPS,D1,D3,D2,D4);
Servo myservo;
Servo myservo2;
Servo myservo3;
WiFiClient client;
//ESP8266作为服务器连接到WiFi
const char *ssid = "xxx"; //要连接的WiFi名称
const char *password = "xxx"; //要连接WiFi的密码
int pos2,pos3;
int beforepos2,beforepos3;
int count = 32;
int value = 0;
int pitch,roll;
int signal = 0;
// 复位或上电后运行一次:
void setup() {
//在这里加入初始化相关代码,只运行一次:
Serial.begin(9600);
pinMode(key,INPUT_PULLUP);
WiFi.mode(WIFI_STA);
WiFi.begin(ssid, password); //连接WiFi
// stepper.setSpeed(20);
myservo.attach(D5);
myservo2.attach(D6);
myservo3.attach(D7);
// myservo.write(pos);
// 等待ESP8266连接上WiFi
Serial.println("Connecting to Wifi");
while (WiFi.status() != WL_CONNECTED) {
Serial.print(".");
delay(50);
}
Serial.println("");
Serial.print("Connected to ");
Serial.println(ssid);
Serial.print("IP address: ");
Serial.println(WiFi.localIP());
Serial.print("port:");
Serial.println(port);
server.begin();
}
//一直循环执行:
void loop() {
// 在这里加入主要程序代码,重复执行:
client = server.available();
if (client) {
if(client.connected())
{
Serial.println("Client Connected");
}
while(client.connected()){ //WiFi连接上后循环执行下面的代码
getCom();
beforepos2 = pos2;
beforepos3 = pos3;
pos2 = map(pitch,0,90,100,180); //后面两个参数100,180改成组装机械臂后舵机能旋转的角度范围
pos3 = map(roll,-90,90,0,180);
if(signal == 1)
{
Holder();
armControl();
signal = 0;
client.write(signal);
}
// yield();
}
client.stop();
Serial.println("Client disconnected");
}
}
void getCom() //获取客户端发送的命令
{
if(client.available()>0) //判断ESP8266缓冲区是否有数据
{
pitch=client.parseInt(); //parseInt函数将第一个整型数据赋值给pitch,并将缓冲区的数据删除
roll=client.parseInt(); //第一个整型数据赋值给了pitch,并删除了缓冲区的数据,所以第二个数据变成了第一个
Serial.print("pitch=");
Serial.print(pitch);
Serial.print(" roll=");
Serial.println(roll);
signal = 1;
}
}
void armControl()
{
if(pitch>15&&roll>-20&&roll<20) //控制机械臂前臂的上下运动
{
if(pos2>=beforepos2)
{
for(int i=beforepos2;i<=pos2;i++)
{
myservo2.write(i);
delay(10);
}
}
else if(pos2<beforepos2)
{
for(int i=beforepos2;i>=pos2;i--)
{
myservo2.write(i);
delay(10);
}
}
}
if(roll>15&&roll<90&&roll>-90&&roll<-15) //底座舵机
{
if(pos3>=beforepos3)
{
for(int i=beforepos3;i<=pos3;i++)
{
myservo3.write(i);
delay(10);
}
}
else if(pos3<beforepos3)
{
for(int i=beforepos3;i>=pos3;i--)
{
myservo3.write(i);
delay(10);
}
}
}
// if(pitch>15&&roll>20) //底座步进电机控制机械臂左右运动
// {
// if(count>=64) //控制步进电机在一定范围内转动
// return;
// stepper.step(8);
// count++;
// Serial.println(count);
// }
//
// if(pitch>15&&roll<-20)
// {
// if(count<=0)
// return;
// stepper.step(-8);
// count--;
// Serial.println(count);
// }
}
void Holder() //按键控制夹子的开合
{
value = digitalRead(key);
if(value == HIGH)
{
if(pos == 110) //这里的角度110,30也改成你组装成机械臂后舵机实际的旋转角度范围
{
for (pos; pos>30; pos--)
{
myservo.write(pos);
Serial.println(pos);
delay(20);
}
}
else if(pos == 30)
{
for (pos; pos<110; pos++)
{
myservo.write(pos);
Serial.println(pos);
delay(20);
}
}
}
}
通过零知IDE将以上代码分别上传至两块ESP8266开发板
完成以上步骤,我们就可以通过三轴加速度传感器来控制机械臂了。视频效果请见下一楼。