|
【R311】双轴XY平台
作者:机器谱
绘制斜向多边形 绘制斜向多边形2 绘制正弦曲线 绘制正弦曲线2 |
绘制斜向多边形
1. 功能说明
本文示例将实现R311样机双轴XY平台绘制斜向多边形的功能。
2. 直角坐标机器人的结构设计
直角坐标机器人各个运动轴通常对应直角坐标系中的X轴、Y轴和Z 轴,其中X 轴和Y 轴是水平面内运动轴,Z轴是上下运动轴。在绝大多数情况下直角坐标机器人的各个直线运动轴间的夹角为直角。
直角坐标系根据自由度可分为单轴、双轴和三轴直角坐标系机械臂,每个轴互相垂直且单轴沿着直线方向运动。
直角坐标系机器人的最基础功能模块为直线运动的单轴模块,在单轴机模块中常见的传动方式有两种:一种是丝杆传动,另一种是同步带(同步齿形带)传动。这两种传动方式都是以直线导轨作为导向的,配合伺服电机或步进电机,可实现不同应用领域的定位、移载、搬运等。
这里主要介绍下丝杠传动机构原理:这是一个将转动转化为平动的机构,丝杠与移动的滑块之间通过螺纹传动;电机的旋转运动通过丝杆传递给滑块,由于滑块被支架限制不能进行旋转运动,所以滑块最终将旋转的运动转换为水平方向的移动。
运动特性:通过上面的分析可以看出,这是一种螺旋机构,具有以下特点
(1) 回转运动变换为直线运动,运动准确性高,且有很大的降速比;复式螺旋可以获得较大的位移,差动螺旋可以获得微小的位移;
(2) 结构简单,制造方便;
(3) 工作平稳,无噪声,可以传递很大的轴向力;
(4) 传动效率低,有自锁作用,相对运动表面磨损较快;
(5) 实现往复运动要靠主动件改变转动方向。
丝杠机构的的稳定性很好,可以承受较大的力,所以如果要设计一些直线运输重物的机构时,可以考虑利用丝杠来实现。
本实验将利用双轴XY丝杠平台来绘制斜向多边形。
3. 电子硬件
在这个示例中,采用了以下硬件,请大家参考:
主控板 | |
扩展板 | |
SH-ST步进电机扩展板 | |
电池 | 11.1V动力电池 |
传感器 | 触碰传感器 |
其它 | 笔架×1(自制,可根据文末资料提供的3D文件打印) |
例:绘制第1象限直线OA,起点为O(0,0),终点为A (6,4),试进行插补并作走步轨迹图。 解:进给总步数 Nxy =|6-0|+|4-0|=10 xe=6,ye=4, F0 = 0, xoy=1 |
/*------------------------------------------------------------------------------------ 版权说明:Copyright 2023 Robottime(Beijing) Technology Co., Ltd. All Rights Reserved. Distributed under MIT license.See file LICENSE for detail or copy at https://opensource.org/licenses/MIT by 机器谱 2023-03-24 https://www.robotway.com/ ------------------------------*/ #define EN 8 //步进电机使能端,低电平有效 #define X_DIR 5 //X轴 步进电机方向控制 #define Y_DIR 6 //y轴 步进电机方向控制 #define X_STP 2 //x轴 步进控制 #define Y_STP 3 //y轴 步进控制 boolean DIR; //boolean类型变量 DIR,控制步进电机方向,true为正向,false为反向,根据接线做调整 int stepper_delay = 40; //定义步进电机脉冲发送的时间间隔 const int SENSOR_X = 18; //定义X方向复位传感器引脚 const int SENSOR_Y = 14; //定义y方向复位传感器引脚 const int SENSOR_TOUCH = 16; //定义电机运动的触发传感器引脚 const int stepsPerRevolution = 3200; //定义步进电机每圈转动的步数,细分为16 float LEAD = 8.0; //定义丝杠导程,即步进电机转动一圈,丝杠前进8mm float DIAGONAL_A = 20; //定义多边形两条对角线长度 float DIAGONAL_B = 30; float Xmin = 0; float Xmax = sqrt((DIAGONAL_A/2)*(DIAGONAL_A/2)+(DIAGONAL_B/2)*(DIAGONAL_B/2)); //多边形X方向边长 float Ymin = 0; float Ymax = (2*DIAGONAL_A/2*DIAGONAL_B/2)/Xmax; //多边形Y方向的高 float x1 = 0; //多边形四个顶点的坐标 float y1 = 0; float x2 = Xmax; float y2 = 0; float x3 = (2*DIAGONAL_B/2*DIAGONAL_B/2-Xmax*Xmax)/Xmax+Xmax; float y3 = Ymax; float x4 = (2*DIAGONAL_B/2*DIAGONAL_B/2-Xmax*Xmax)/Xmax; float y4 = Ymax; void setup() { Serial.begin(9600); //开启串口通信,波特率为9600 pinMode(X_DIR, OUTPUT); pinMode(X_STP, OUTPUT); pinMode(Y_DIR, OUTPUT); pinMode(Y_STP, OUTPUT); pinMode(EN, OUTPUT); digitalWrite(EN, LOW); resetStepper(); } void loop() { while(digitalRead(SENSOR_TOUCH)) delay(10);
step(Y_DIR,Y_STP,-40000); step(X_DIR, X_STP, 24000);
runIn(x1, y1, x2, y2);
runIn(x2, y2, x3, y3);
runIn(x3, y3, x4, y4);
runIn(x4, y4, x1, y1);
resetStepper(); } //四象限直线插补函数,参数为两个点的坐标值 void runIn(float x1, float y1, float x2, float y2) { /* dx:X轴两坐标间步数值 dy:Y轴两坐标间步数值 n :两坐标X轴和Y轴总步数 k :象限值 f :偏差计算值 stepInc:步进电机转动步数 */ int dx, dy, n, k, i, f, stepInc; dx = abs((x2-x1)/LEAD*stepsPerRevolution); dy = abs((y2-y1)/LEAD*stepsPerRevolution); n = abs(dx+dy); if(dx==0||dy==0) { stepper_delay = 40; stepInc = 10; } else { stepper_delay = 200; stepInc = 100; }
if(x2 >= x1) { k = y2 >= y1 ? 1:4; } else { k = y2 >= y1 ? 2:3; }
for(i=0,f=0;i<n;i+=stepInc) { if(f>=0) { switch(k) { case 1: step(X_DIR, X_STP, stepInc); f = f - dy; //Serial.println("+x"); break; case 2: step(X_DIR, X_STP, -stepInc); f = f - dy; //Serial.println("-x"); break; case 3: step(X_DIR, X_STP, -stepInc); f = f - dy; //Serial.println("-x"); break; case 4: step(X_DIR, X_STP, stepInc); f = f - dy; //Serial.println("+x"); break; default:break; } } else { switch(k) { case 1: step(Y_DIR, Y_STP, stepInc); f = f + dx; //Serial.println("+y"); break; case 2: step(Y_DIR, Y_STP, stepInc); f = f + dx; //Serial.println("+y"); break; case 3: step(Y_DIR, Y_STP, -stepInc); f = f + dx; //Serial.println("-y"); break; case 4: step(Y_DIR, Y_STP, -stepInc); f = f +dx; //Serial.println("-y"); break; default:break; } } } } /* //函数:step 功能:控制步进电机方向,步数。 //参数:dirPin对应步进电机的DIR引脚,stepperPin 对应步进电机的step引脚, steps 步进的步数 //无返回值 */ void step(byte dirPin, byte stepperPin, int steps) { boolean DIR = steps>0 ? true : false; digitalWrite(dirPin,DIR); for(int i=0;i<abs(steps); i++) { digitalWrite(stepperPin, HIGH); delayMicroseconds(stepper_delay); digitalWrite(stepperPin, LOW); delayMicroseconds(stepper_delay); } } //步进电机复位函数 void resetStepper() { stepper_delay = 40; while(digitalRead(SENSOR_X)) step(X_DIR,X_STP,-10); step(X_DIR,X_STP,15); while(digitalRead(SENSOR_Y)) step(Y_DIR,Y_STP,-10); step(Y_DIR,Y_STP,15); } |
4. 功能实现
在这里我们采用了一种算法,该算法的思路是:先建立一个平面坐标系,将我们所需要画的多边形图形放置在该坐标系中,这样就可以确定该图形每个顶点的坐标,两个相邻的顶点之间确定一条直线,直线上各点坐标通过插补计算得到,然后画笔依次沿着这些坐标进行移动,完成绘制。所以在这个过程中,我们需要知道如何建立一个图形的坐标系,以及什么是插补计算,下面我们通过1个菱形图案进行相关算法讲解。
建立坐标系:
我们建立一个以A点为原点的直角坐标系,很容易可以得出其顶点坐标:A(0,0),B(X,0),C(X+X1,Y),D(X1,Y);其中菱形的对角线为已知量a,b。
通过勾股定理很容易得出:
这样菱形的4个顶点坐标就确定了,接下来需要考虑如何控制双轴平台实现在坐标系内的直线运动。双轴平台实现直线的轨迹运动需要X轴和Y轴共同协作,但是X轴和Y轴在运动时始终存在一个时间差,所以在绘制斜向直线时,实际是由无数的折线段组成的,当这些折线无限小时,这些折线看起来就是一条直线了。
这里我们采用在数控加工中所用的曲线加工方法-插补计算。
插补计算:
对轮廓线的起点到终点之间再密集的计算出有限个坐标单,执行端沿着这些坐标点移动,用折线逼近所要绘制的曲线。
这里我们采用逐点比较法插补计算: 绘图笔每走一步都要和给定轨迹上的坐标值进行比较一次,根据这个比较判断偏差方向,决定下一步的进给方向。
插补步骤:
偏差判别(根据偏差确定下一步走向) > 坐标进给(走一步) > 偏差计算(判断偏差方向) > 终点判断(插补结束判断)。
所以在这个过程中,我们首先需要知道如何进行偏差方向的判断(偏差判别),知道对应的双轴平台X/Y向如何进给。
常规的方法是引入一个偏差量Fm,通过判断Fm的值和终点所在象限来判断进给方向,当Fm≥0时且终点在一、四象限时,沿﹢X方向进给,在二、三象限时,沿-X向进给;当Fm<0时且终点在一、二象限时,沿﹢Y方向进给,在三、四象限时,沿-Y向进给。如下表所示:
4.1硬件连接
按下图所示,在双轴XY平台的①和②位置安装两个触碰传感器,用作开关限位器:
电路连接说明:
① 步进电机:
X轴黑绿红蓝 Y轴黑绿红蓝
② 触碰传感器3个↓
X方向复位传感器引脚:A4
y方向复位传感器引脚:A0
电机运动的触发传感器引脚:A2
4.2 示例程序
编程环境:Arduino 1.8.19
参考下列例程代码(_2_new.ino),输入不同的a,b值,完成菱形的绘制:
5. 资料清单
序号 | 内容 |
1 | 【R311】-绘制斜向多边形-例程源代码 |
2 | 【R311】-绘制斜向多边形-样机3D文件 |
【整体打包】-【R311】双轴XY平台-绘制斜向多边形-资料附件.zip | 2.7MB | 下载10次 | 下载 |
绘制斜向多边形2
1. 功能描述
本文示例将实现R311a样机双轴XY平台绘制斜向多边形的功能。
2. 结构说明
该机构是由一个X轴和一个Y轴分布的丝杠平台组合而成,X轴位于图中底部的丝杠,Y轴为顶部的丝杠。
注意限位开关的安装和一个启动XY平台的开关传感器安装:
3. 电子硬件
在这个示例中,我们采用了以下硬件,请大家参考:
电路连接:
步进电机电路连接示意图
Bigfish扩展板上电路连接示意图
① X轴步进电机传感器连在Bigfish扩展板的A4端口
② Y轴步进电机传感器连在Bigfish扩展板的A0端口
4. 功能实现
编程环境:Arduino 1.8.19
功能:实现双轴XY平台绘制菱形。
下面提供一个参考程序(Double_Axis.ino):
/*------------------------------------------------------------------------------------ 版权说明:Copyright 2023 Robottime(Beijing) Technology Co., Ltd. All Rights Reserved. Distributed under MIT license.See file LICENSE for detail or copy at https://opensource.org/licenses/MIT by 机器谱 2024-02-01 https://www.robotway.com/ ------------------------------*/ #define EN 8 //步进电机使能端,低电平有效 #define X_DIR 5 //X轴 步进电机方向控制 #define Y_DIR 6 //y轴 步进电机方向控制 #define X_STP 2 //x轴 步进控制 #define Y_STP 3 //y轴 步进控制 boolean DIR; //boolean类型变量 DIR,控制步进电机方向,true为正向,false为反向,根据接线做调整 int stepper_delay = 40; //定义步进电机脉冲发送的时间间隔
const int SENSOR_X = 18; //定义X方向复位传感器引脚 const int SENSOR_Y = 14; //定义y方向复位传感器引脚 const int SENSOR_TOUCH = 16; //定义电机运动的触发传感器引脚
const int stepsPerRevolution = 3200; //定义步进电机每圈转动的步数,细分为16
float LEAD = 8.0; //定义丝杠导程,即步进电机转动一圈,丝杠前进8mm
float DIAGONAL_A = 20; //定义多边形两条对角线长度 float DIAGONAL_B = 30;
float Xmin = 0; float Xmax = sqrt((DIAGONAL_A/2)*(DIAGONAL_A/2)+(DIAGONAL_B/2)*(DIAGONAL_B/2)); //多边形X方向边长 float Ymin = 0; float Ymax = (2*DIAGONAL_A/2*DIAGONAL_B/2)/Xmax; //多边形Y方向的高
float x1 = 0; //多边形四个顶点的坐标 float y1 = 0; float x2 = Xmax; float y2 = 0; float x3 = (2*DIAGONAL_B/2*DIAGONAL_B/2-Xmax*Xmax)/Xmax+Xmax; float y3 = Ymax; float x4 = (2*DIAGONAL_B/2*DIAGONAL_B/2-Xmax*Xmax)/Xmax; float y4 = Ymax;
void setup() { Serial.begin(9600); //开启串口通信,波特率为9600 pinMode(X_DIR, OUTPUT); pinMode(X_STP, OUTPUT); pinMode(Y_DIR, OUTPUT); pinMode(Y_STP, OUTPUT); pinMode(EN, OUTPUT); digitalWrite(EN, LOW); resetStepper(); }
void loop() { while(digitalRead(SENSOR_TOUCH)) delay(10);
// step(Y_DIR,Y_STP,-40000); // step(X_DIR, X_STP, 24000);
runIn(x1, y1, x2, y2);
runIn(x2, y2, x3, y3);
runIn(x3, y3, x4, y4);
runIn(x4, y4, x1, y1);
resetStepper(); }
//四象限直线插补函数,参数为两个点的坐标值 void runIn(float x1, float y1, float x2, float y2) { /* dx:X轴两坐标间步数值 dy:Y轴两坐标间步数值 n :两坐标X轴和Y轴总步数 k :象限值 f :偏差计算值 stepInc:步进电机转动步数 */ int dx, dy, n, k, i, f, stepInc; dx = abs((x2-x1)/LEAD*stepsPerRevolution); dy = abs((y2-y1)/LEAD*stepsPerRevolution); n = abs(dx+dy); if(dx==0||dy==0) { stepper_delay = 40; stepInc = 10; } else { stepper_delay = 200; stepInc = 100; }
if(x2 >= x1) { k = y2 >= y1 ? 1:4; } else { k = y2 >= y1 ? 2:3; }
for(i=0,f=0;i<n;i+=stepInc) { if(f>=0) { switch(k) { case 1: step(X_DIR, X_STP, stepInc); f = f - dy; //Serial.println("+x"); break; case 2: step(X_DIR, X_STP, -stepInc); f = f - dy; //Serial.println("-x"); break; case 3: step(X_DIR, X_STP, -stepInc); f = f - dy; //Serial.println("-x"); break; case 4: step(X_DIR, X_STP, stepInc); f = f - dy; //Serial.println("+x"); break; default:break; } } else { switch(k) { case 1: step(Y_DIR, Y_STP, stepInc); f = f + dx; //Serial.println("+y"); break; case 2: step(Y_DIR, Y_STP, stepInc); f = f + dx; //Serial.println("+y"); break; case 3: step(Y_DIR, Y_STP, -stepInc); f = f + dx; //Serial.println("-y"); break; case 4: step(Y_DIR, Y_STP, -stepInc); f = f +dx; //Serial.println("-y"); break; default:break; } } } }
/* //函数:step 功能:控制步进电机方向,步数。 //参数:dirPin对应步进电机的DIR引脚,stepperPin 对应步进电机的step引脚, steps 步进的步数 //无返回值 */ void step(byte dirPin, byte stepperPin, int steps) { boolean DIR = steps>0 ? true : false; digitalWrite(dirPin,DIR); for(int i=0;i<abs(steps); i++) { digitalWrite(stepperPin, HIGH); delayMicroseconds(stepper_delay); digitalWrite(stepperPin, LOW); delayMicroseconds(stepper_delay); } }
//步进电机复位函数 void resetStepper() { stepper_delay = 40; while(digitalRead(SENSOR_X)) step(X_DIR,X_STP,-10); step(X_DIR,X_STP,15); while(digitalRead(SENSOR_Y)) step(Y_DIR,Y_STP,-10); step(Y_DIR,Y_STP,15); } |
5. 资料清单
序号 | 内容 |
1 | 【R311】-绘制斜向多边形2-程序源代码 |
2 | 【R311】-绘制斜向多边形2-样机3D文件 |
样机方案-【R311】双轴XY平台-绘制斜向多边形2-资料附件.rar | 3.95MB | 下载1次 | 下载 |
绘制正弦曲线
1. 功能说明
本文示例将实现R311样机双轴XY平台绘制正弦曲线的功能。
2. 电子硬件
在这个示例中,采用了以下硬件,请大家参考:
主控板 | |
扩展板 | |
电池 | 11.1V动力电池 |
传感器 | 触碰传感器 |
其它 | 笔架×1(自制) |
/*------------------------------------------------------------------------------------ 版权说明:Copyright 2023 Robottime(Beijing) Technology Co., Ltd. All Rights Reserved. Distributed under MIT license.See file LICENSE for detail or copy at https://opensource.org/licenses/MIT by 机器谱 2023-03-27 https://www.robotway.com/ ------------------------------*/ #define EN 8 //步进电机使能端,低电平有效 #define X_DIR 5 //X轴 步进电机方向控制 #define Y_DIR 6 //y轴 步进电机方向控制 #define X_STP 2 //x轴 步进控制 #define Y_STP 3 //y轴 步进控制 boolean DIR; //boolean类型变量 DIR,控制步进电机方向,true为正向,false为反向,根据接线做调整 int stepper_delay = 40; //定义步进电机脉冲发送的时间间隔 const int SENSOR_X = 18; //定义X方向复位传感器引脚 const int SENSOR_Y = 14; //定义y方向复位传感器引脚 const int SENSOR_TOUCH = 16; //定义电机运动的触发传感器引脚 const int stepsPerRevolution = 3200; //定义步进电机每圈转动的步数,细分为16 float LEAD = 0.8; //定义丝杠导程,即步进电机转动一圈,丝杠前进8cm float A = 2.0; //定义sin函数振幅 float W = 1.0; //定义sin函数角频率 float P = 0.0; //定义sin函数初始相位 float Xmin = 0; float Ymin = 0; float Xpos = Xmin; float Ypos = Ymin; void setup() { Serial.begin(9600); //开启串口通信,波特率为9600 pinMode(X_DIR, OUTPUT); pinMode(X_STP, OUTPUT); pinMode(Y_DIR, OUTPUT); pinMode(Y_STP, OUTPUT); pinMode(EN, OUTPUT); digitalWrite(EN, LOW); resetStepper(); } void loop() { while(digitalRead(SENSOR_TOUCH)) delay(10);
Xpos = 0; Ypos = 0;
step(Y_DIR,Y_STP,-40000); //step(X_DIR, X_STP, 28000);
for(float x=0;x<=2*PI/W;x+=0.1) { float y = A*sin(W*x+P); drawLine(x,y); }
step(X_DIR, X_STP, 8000);
resetStepper(); } //图形绘制函数,参数为点坐标值 void drawLine(float x1, float y1) { int dx, dy, n, k, i, f, stepInc; x1 = (int)(x1/LEAD*stepsPerRevolution); y1 = (int)(y1/LEAD*stepsPerRevolution); float x0 = Xpos; float y0 = Ypos;
Serial.println(Xpos); Serial.println(Ypos);
dx = abs(x1-x0); dy = abs(y1-y0); n = abs(dx+dy); if(dx==0||dy==0) { stepper_delay = 40; stepInc = 10; } else { stepper_delay = 200; stepInc = 100; }
if(x1 >= x0) { k = y1 >= y0 ? 1:4; } else { k = y1 >= y0 ? 2:3; }
for(i=0,f=0;i<n;i+=stepInc) { if(f>=0) { switch(k) { case 1: step(X_DIR, X_STP, stepInc); f = f - dy; //Serial.println("+x"); break; case 2: step(X_DIR, X_STP, -stepInc); f = f - dy; //Serial.println("-x"); break; case 3: step(X_DIR, X_STP, -stepInc); f = f - dy; //Serial.println("-x"); break; case 4: step(X_DIR, X_STP, stepInc); f = f - dy; //Serial.println("+x"); break; default:break; } } else { switch(k) { case 1: step(Y_DIR, Y_STP, stepInc); f = f + dx; //Serial.println("+y"); break; case 2: step(Y_DIR, Y_STP, stepInc); f = f + dx; //Serial.println("+y"); break; case 3: step(Y_DIR, Y_STP, -stepInc); f = f + dx; //Serial.println("-y"); break; case 4: step(Y_DIR, Y_STP, -stepInc); f = f +dx; //Serial.println("-y"); break; default:break; } } } Xpos = x1; Ypos = y1; } /* //函数:step 功能:控制步进电机方向,步数。 //参数:dirPin对应步进电机的DIR引脚,stepperPin 对应步进电机的step引脚, steps 步进的步数 //无返回值 */ void step(byte dirPin, byte stepperPin, int steps) { boolean DIR = steps>0 ? true : false; digitalWrite(dirPin,DIR); for(int i=0;i<abs(steps); i++) { digitalWrite(stepperPin, HIGH); delayMicroseconds(stepper_delay); digitalWrite(stepperPin, LOW); delayMicroseconds(stepper_delay); } } //步进电机复位函数 void resetStepper() { stepper_delay = 40; while(digitalRead(SENSOR_X)) step(X_DIR,X_STP,-10); step(X_DIR,X_STP,15); while(digitalRead(SENSOR_Y)) step(Y_DIR,Y_STP,-10); step(Y_DIR,Y_STP,15); } |
3. 功能实现
绘制正弦曲线同样采用建立坐标系,确定特殊点坐标,利用插补法来完成坐标路径绘制。
正弦曲线:
3.1硬件连接
按下图所示,在双轴XY平台的①和②位置安装两个触碰传感器,用作开关限位器:
电路连接说明:
① 步进电机:
X轴黑绿红蓝 Y轴黑绿红蓝
② 触碰传感器3个↓
X方向复位传感器引脚:A4
y方向复位传感器引脚:A0
电机运动的触发传感器引脚:A2
3.2 示例程序
编程环境:Arduino 1.8.19
下面提供一个正弦函数为 的参考例程(_3_sin.ino),尝试读懂程序,绘制不同参数的正弦曲线:
4. 资料清单
序号 | 内容 |
1 | 【R311】-绘制正弦曲线-例程源代码 |
【整体打包】-【R311】双轴XY平台-绘制正弦曲线-资料附件.zip | 3.97KB | 下载1次 | 下载 |
绘制正弦曲线2
1. 功能描述
本文示例将实现R311a样机双轴XY平台绘制正弦曲线的功能。
2. 电子硬件
在这个示例中,我们采用了以下硬件,请大家参考:
电路连接:
步进电机电路连接示意图
Bigfish扩展板上电路连接示意图
① X轴步进电机传感器连在Bigfish扩展板的A4端口
② Y轴步进电机传感器连在Bigfish扩展板的A0端口
3. 功能实现
绘制正弦曲线同样采用建立坐标系,确定特殊点坐标,利用插补法完成坐标路径绘制。只是绘制正弦曲线和绘制多边形的算法不一样。
正弦曲线: Y = Asin(wX +φ)
编程环境:Arduino 1.8.19
下面提供一个正弦函数为Y= 2sinX,XÎ[0,2π] 的参考程序(Double_Axis_Draw_Sin.ino):
/*------------------------------------------------------------------------------------ 版权说明:Copyright 2023 Robottime(Beijing) Technology Co., Ltd. All Rights Reserved. Distributed under MIT license.See file LICENSE for detail or copy at https://opensource.org/licenses/MIT by 机器谱 2024-02-02 https://www.robotway.com/ ------------------------------*/ #define EN 8 //步进电机使能端,低电平有效 #define X_DIR 5 //X轴 步进电机方向控制 #define Y_DIR 6 //y轴 步进电机方向控制 #define X_STP 2 //x轴 步进控制 #define Y_STP 3 //y轴 步进控制 boolean DIR; //boolean类型变量 DIR,控制步进电机方向,true为正向,false为反向,根据接线做调整 int stepper_delay = 40; //定义步进电机脉冲发送的时间间隔
const int SENSOR_X = 18; //定义X方向复位传感器引脚 const int SENSOR_Y = 14; //定义y方向复位传感器引脚 const int SENSOR_TOUCH = 16; //定义电机运动的触发传感器引脚
const int stepsPerRevolution = 3200; //定义步进电机每圈转动的步数,细分为16
float LEAD = 0.8; //定义丝杠导程,即步进电机转动一圈,丝杠前进8cm
float A = 1.0; //定义sin函数振幅 float W = 1.0; //定义sin函数角频率 float P = 0.0; //定义sin函数初始相位
float Xmin = 0; float Ymin = 0;
float Xpos = Xmin; float Ypos = Ymin;
void setup() { Serial.begin(9600); //开启串口通信,波特率为9600 pinMode(X_DIR, OUTPUT); pinMode(X_STP, OUTPUT); pinMode(Y_DIR, OUTPUT); pinMode(Y_STP, OUTPUT); pinMode(EN, OUTPUT); digitalWrite(EN, LOW); resetStepper(); }
void loop() { while(digitalRead(SENSOR_TOUCH)) delay(10);
Xpos = 0; Ypos = 0;
step(Y_DIR,Y_STP,-40000); //step(X_DIR, X_STP, 28000);
for(float x=0;x<=2*PI/W;x+=0.1) { float y = A*sin(W*x+P); drawLine(x,y); }
step(X_DIR, X_STP, 8000);
resetStepper(); }
//图形绘制函数,参数为点坐标值 void drawLine(float x1, float y1) { int dx, dy, n, k, i, f, stepInc; x1 = (int)(x1/LEAD*stepsPerRevolution); y1 = (int)(y1/LEAD*stepsPerRevolution); float x0 = Xpos; float y0 = Ypos;
Serial.println(Xpos); Serial.println(Ypos);
dx = abs(x1-x0); dy = abs(y1-y0); n = abs(dx+dy); if(dx==0||dy==0) { stepper_delay = 40; stepInc = 10; } else { stepper_delay = 200; stepInc = 100; }
if(x1 >= x0) { k = y1 >= y0 ? 1:4; } else { k = y1 >= y0 ? 2:3; }
for(i=0,f=0;i<n;i+=stepInc) { if(f>=0) { switch(k) { case 1: step(X_DIR, X_STP, stepInc); f = f - dy; //Serial.println("+x"); break; case 2: step(X_DIR, X_STP, -stepInc); f = f - dy; //Serial.println("-x"); break; case 3: step(X_DIR, X_STP, -stepInc); f = f - dy; //Serial.println("-x"); break; case 4: step(X_DIR, X_STP, stepInc); f = f - dy; //Serial.println("+x"); break; default:break; } } else { switch(k) { case 1: step(Y_DIR, Y_STP, stepInc); f = f + dx; //Serial.println("+y"); break; case 2: step(Y_DIR, Y_STP, stepInc); f = f + dx; //Serial.println("+y"); break; case 3: step(Y_DIR, Y_STP, -stepInc); f = f + dx; //Serial.println("-y"); break; case 4: step(Y_DIR, Y_STP, -stepInc); f = f +dx; //Serial.println("-y"); break; default:break; } } } Xpos = x1; Ypos = y1; }
/* //函数:step 功能:控制步进电机方向,步数。 //参数:dirPin对应步进电机的DIR引脚,stepperPin 对应步进电机的step引脚, steps 步进的步数 //无返回值 */ void step(byte dirPin, byte stepperPin, int steps) { boolean DIR = steps>0 ? true : false; digitalWrite(dirPin,DIR); for(int i=0;i<abs(steps); i++) { digitalWrite(stepperPin, HIGH); delayMicroseconds(stepper_delay); digitalWrite(stepperPin, LOW); delayMicroseconds(stepper_delay); } }
//步进电机复位函数 void resetStepper() { stepper_delay = 40; while(digitalRead(SENSOR_X)) step(X_DIR,X_STP,-10); step(X_DIR,X_STP,15); while(digitalRead(SENSOR_Y)) step(Y_DIR,Y_STP,-10); step(Y_DIR,Y_STP,15); } |
4. 资料清单
序号 | 内容 |
1 | 【R311】-绘制正弦曲线2-程序源代码 |
2 | 【R311】-绘制正弦曲线2-样机3D文件 |
样机方案-【R311】双轴XY平台-绘制正弦曲线2-资料附件.rar | 3.95MB | 下载2次 | 下载 |