我所建的为三自由度连杆机械臂,选择搭建这款机械臂主要是因为此机械臂操作简单,易于掌握,便于学习。
以下为我在学习制造这款机械臂的一些流程:
主要零件
主控板:arduino uno r3
扩展板:cnc shield v3雕刻机扩展板
42步进电机,SG90电机,PVC板,A4988驱动模块,HC-06模块
由于我做一件事喜欢把它列出来,所以做了思维导图:
以下为代码部分:
在代码部分中,由于本人编程能力较弱,一部分代码和编程思维均借鉴了多位B站UP主,并且本文章仅为记录我学习机械臂的过程。
手机模式和键盘模式代码:
/*电机步进模式须在cnc电机扩展版上进行调试。
* 启动程序,程序开始默认为键盘控制模式
* 在键盘模式中,'m'可一键切换至手机模式。
* 手机模式
* 在手机模式中,'m'可一键切换至键盘模式。
*/
#include <Servo.h>
#include <AccelStepper.h>
#include <SoftwareSerial.h>
SoftwareSerial BTserial(12, 13); // 建立SoftwareSerial对象,RX引脚12(SpnEn)接SpnDir, TX引脚13(SpnDir)接SpnEn
// 定义电机控制用常量
const int enablePin = 8; // 使能控制引脚
const int xdirPin = 5; // x方向控制引脚
const int xstepPin = 2; // x步进控制引脚
const int ydirPin = 6; // y方向控制引脚
const int ystepPin = 3; // y步进控制引脚
const int zdirPin = 7; // z方向控制引脚
const int zstepPin = 4; // z步进控制引脚
const int clawMin = 144; //存储电机极限值
const int clawMax = 180;
const int moveSteps = 5; //步进电机运行使用的运行步数(仅适用于手机模式)
char cmd; //电机指令字符
int data; //电机指令参数
char stepperName; //控制电机编号
int stepNumber; //步进电机运行步数
int clawstep; //夹爪电机的目标角度
bool mode = 1; //mode = 1: 键盘模式, mode = 0: 手机模式
int DSD = 15; //Default Servo Delay (默认电机运动延迟时间)
//此变量用于控制电机运行速度.增大此变量数值将
//降低电机运行速度从而控制机械臂动作速度。
int clawMoveStep = 2; // 每一次按下手柄按键,舵机移动量(仅适用于手机模式)
Servo claw ; //建立伺服电机对象———夹爪电机
AccelStepper base_stepper(1,xstepPin,xdirPin); //建立步进电机对象———底座电机
AccelStepper forearm_stepper(1,ystepPin,ydirPin); //建立步进电机对象———前臂电机
AccelStepper upperarm_stepper(1,zstepPin,zdirPin); //建立步进电机对象———后臂电机
void setup() {
pinMode(xstepPin,OUTPUT); // Arduino控制A4988x步进引脚为输出模式
pinMode(xdirPin,OUTPUT); // Arduino控制A4988x方向引脚为输出模式
pinMode(ystepPin,OUTPUT); // Arduino控制A4988y步进引脚为输出模式
pinMode(ydirPin,OUTPUT); // Arduino控制A4988y方向引脚为输出模式
pinMode(zstepPin,OUTPUT); // Arduino控制A4988z步进引脚为输出模式
pinMode(zdirPin,OUTPUT); // Arduino控制A4988z方向引脚为输出模式
pinMode(enablePin,OUTPUT); // Arduino控制A4988使能引脚为输出模式
digitalWrite(enablePin,LOW); // 将使能控制引脚设置为低电平从而让
// 电机驱动板进入工作状态
claw.attach(11); // claw 伺服舵机连接引脚Z+ 舵机代号'c'
delay(200); // 稳定性等待
claw.write(90);
delay(10);
Serial.begin(9600);
BTserial.begin(9600); // HC-06 默认波特率 9600
Serial.println(F("/\\\\\\\\\\\\\\\\\\"));
Serial.println(F("****The robotic arm serves you*****"));
Serial.println(F("/\\\\\\\\\\\\\\\\\\"));
Serial.println(F(""));
Serial.println(F("Please input motor command:"));
Serial.print("HC-06 DEMO/TEST ");
BTserial.print("AT"); //可在此处输入设置HC-06蓝牙模块的AT指令。
//此AT指令须在HC-06未连接蓝牙状态输入。
base_stepper.setMaxSpeed(100); // 设置电机最大速度为500
base_stepper.setAcceleration(50.0); // 初始化电机速度为0 setSpeed(0);
forearm_stepper.setMaxSpeed(100);
forearm_stepper.setAcceleration(50.0);
upperarm_stepper.setMaxSpeed(100);
upperarm_stepper.setAcceleration(50.0);
claw.write(144);
base_stepper.setCurrentPosition(0);
forearm_stepper.setCurrentPosition(0);
upperarm_stepper.setCurrentPosition(0);
}
void loop() {
if (Serial.available()>0) { //Serial.available()>0 //BTserial.available()>0
cmd = Serial.read();
Serial.print(cmd);
if( mode == 1 ){
keyboard_input(cmd); //键盘控制模式
} else {
cellphone_input(cmd); //手机控制模式
}
}
base_stepper.run(); //底座电机运行
forearm_stepper.run(); //前臂电机运行
upperarm_stepper.run(); //后臂电机运行
}
//Arduino根据串行指令执行相应操作
//
void keyboard_input(char cmd){
//判断是否因搞错模式而输入错误的指令信息(键盘模式下输入手机模式信息)
if ( cmd == 'w' || cmd == 's' || cmd == 'a' || cmd == 'd'
|| cmd == '5' || cmd == '4' || cmd == '6' || cmd == '8' ){
Serial.println("Warning!!! Warning!!! Warning!!! Currently in the keyboard_input");
delay(100);
while(Serial.available()>0) char wrongCommand = Serial.read(); //清除串口缓存的错误指令
return;
}
if( cmd == 'b' || cmd == 'f' || cmd == 'u'){
data = Serial.parseInt();
RunCommand(cmd,data);
}else{
switch (cmd){
case 'm' ://切换至手机控制模式
mode = 0;
Serial.println("Enter the cellphone control mode");
break;
case 'o' ://使机械臂复位
reset_arm();
Serial.println("Receive command");
break;
case 'c' ://夹爪电机运行
int servoData = Serial.parseInt();
servoCmd(cmd, servoData, DSD); // 机械臂舵机运行函数(参数:舵机名,目标角度,延迟/速度)
Serial.println("Receive the claw operation command");
break;
default : //未知指令反馈
Serial.println("Unknown Command.");
}
}
}
void cellphone_input (char cmd ){
//判断人类是否因搞错模式而输入错误的指令信息(手机模式下输入键盘模式信息)
if (cmd == 'b' || cmd == 'f' || cmd == 'u' || cmd == 'v'){
Serial.println("Warning!!! Warning!!! Warning!!! Currently in the cellphone_input");
delay(100);
while(Serial.available()>0) char wrongCommand = Serial.read(); //清除串口缓存的错误指令
return;
}
int basestep;
int forearmstep;
int upperarmstep;
//int clawstep
switch(cmd){
case 'a' ://base_stepper向左
basestep = base_stepper.currentPosition() - moveSteps;
Serial.println("A run command was received");
delay(500);
base_stepper.moveTo(basestep);
//CellphoneRunCommand('a',basestep);
break;
case 'd' ://base_stepper向右
basestep = base_stepper.currentPosition() + moveSteps;
Serial.println("A run command was received");
delay(500);
base_stepper.moveTo(basestep);
//CellphoneRunCommand('d',basestep);
break;
case 'w' ://upperarm_stepper向下
upperarmstep = upperarm_stepper.currentPosition() - moveSteps;
Serial.println("A run command was received");
delay(500);
upperarm_stepper.moveTo(upperarmstep);
//CellphoneRunCommand('w',upperarmstep);
break;
case 's' ://upperarm_stepper向上
upperarmstep = upperarm_stepper.currentPosition() + moveSteps;
Serial.println("A run command was received");
delay(500);
upperarm_stepper.moveTo(upperarmstep);
//CellphoneRunCommand('s',upperarmstep);
break;
case '8' ://forearm_stepper向下
forearmstep = forearm_stepper.currentPosition() - moveSteps;
Serial.println("A run command was received");
delay(500);
forearm_stepper.moveTo(forearmstep);
//CellphoneRunCommand('8',forearmstep);
break;
case '5' ://forearm_stepper向上
forearmstep = forearm_stepper.currentPosition() + moveSteps;
Serial.println("A run command was received");
delay(500);
forearm_stepper.moveTo(forearmstep);
//CellphoneRunCommand('5',forearmstep);
break;
case '4' ://夹爪打开
Serial.println("Received Command: Claw Open Up");
clawstep = claw.read() - clawMoveStep;
servoCmd('c', clawstep, DSD);
break;
case '6' ://夹爪闭合
Serial.println("Received Command: Claw Close Down");
clawstep = claw.read() + clawMoveStep;
servoCmd('c', clawstep, DSD);
break;
case 'm' : //切换至键盘控制模式
mode = 1;
Serial.println("Enter the keyboard control mode");
break;
case 'o' ://使机械臂复位
reset_arm();
Serial.println("Receive command");
break;
//default : //未知指令反馈
//Serial.println("Unknown Command.");
}
}
void RunCommand(char stepperName,int stepNumber){
switch (stepperName){
case 'b' ://底座电机运行,利用move函数使电机运行相应步数(示例:b1024 - 使电机运行1024步 )
Serial.println("A run command was received");
//delay(500);
base_stepper.move(stepNumber);
break;
case 'f' :
Serial.println("A run command was received");
//delay(500);
forearm_stepper.move(stepNumber);
break;
case 'u' :
Serial.println("A run command was received");
//delay(500);
upperarm_stepper.move(stepNumber);
break;
default: //未知指令反馈
Serial.println("Unknown Command.");
}
}
void reset_arm(){//机械臂复位函数。
/*runToNewPosition与moveTo函数功能基本相同。唯一区别是runToNewPosition函数将“block”程序运行。
* 即电机没有到达目标位置前,Arduino将不会继续执行后续程序内容。
*/
Serial.println("Receive command");
base_stepper.runToNewPosition(0);
forearm_stepper.runToNewPosition(0);
upperarm_stepper.runToNewPosition(0);
claw.write(145);
delay(500);
Serial.println("The reset command was completed");
}
void servoCmd(char servoName, int toPos, int servoDelay){
int fromPos; //建立变量,存储电机起始运动角度值
if(toPos >= clawMin && toPos <= clawMax){
fromPos = claw.read(); // 获取当前电机角度值用于“电机运动起始角度值”
} else {
Serial.println("+Warning: Claw Servo Value Out Of Limit!");
return;
}
//指挥夹爪电机运行
if (fromPos <= toPos){ //如果“起始角度值”小于“目标角度值”
for (int i=fromPos; i<=toPos; i++){
claw.write(i);
delay (15);
}
}else { //否则“起始角度值”大于“目标角度值”
for (int i=fromPos; i>=toPos; i--){
claw.write(i);
delay (15);
Serial.println("Receive command");
}
}
}
坐标自寻代码:
float basepos;
float forearmpos;
float upperarmpos;
float upperarmpos1;
float upperarmpos2;
float pi=3.14;
float touying;
const int basehigh=13;
int duanbian;
int xiebian;
int x;
float y;
float z;
#include <AccelStepper.h>
// 定义电机控制用常量
const int enablePin = 8; // 使能控制引脚
const int xdirPin = 5; // x方向控制引脚
const int xstepPin = 2; // x步进控制引脚
const int ydirPin = 6; // y方向控制引脚
const int ystepPin = 3; // y步进控制引脚
const int zdirPin = 7; // z方向控制引脚
const int zstepPin = 4; // z步进控制引脚
const int Num=6;
const int upperarm=16;
const int forearm=14;
AccelStepper base_stepper(1,xstepPin,xdirPin); //建立步进电机对象———底座电机
AccelStepper forearm_stepper(1,ystepPin,ydirPin); //建立步进电机对象———前臂电机
AccelStepper upperarm_stepper(1,zstepPin,zdirPin); //建立步进电机对象———后臂电机
void setup() {
pinMode(xstepPin,OUTPUT); // Arduino控制A4988x步进引脚为输出模式
pinMode(xdirPin,OUTPUT); // Arduino控制A4988x方向引脚为输出模式
pinMode(ystepPin,OUTPUT); // Arduino控制A4988y步进引脚为输出模式
pinMode(ydirPin,OUTPUT); // Arduino控制A4988y方向引脚为输出模式
pinMode(zstepPin,OUTPUT); // Arduino控制A4988z步进引脚为输出模式
pinMode(zdirPin,OUTPUT); // Arduino控制A4988z方向引脚为输出模式
pinMode(enablePin,OUTPUT); // Arduino控制A4988使能引脚为输出模式
digitalWrite(enablePin,LOW); // 将使能控制引脚设置为低电平从而让
// 电机驱动板进入工作状态
Serial.begin(9600);
Serial.println(F("/\\\\\\\\\\\\\\\\\\"));
Serial.println(F("****The robotic arm serves you*****"));
Serial.println(F("/\\\\\\\\\\\\\\\\\\"));
Serial.println(F(""));
Serial.println(F("Please input motor command:"));
base_stepper.setMaxSpeed(100); // 设置电机最大速度为500
base_stepper.setAcceleration(50.0); // 初始化电机速度为0 setSpeed(0);
forearm_stepper.setMaxSpeed(100);
forearm_stepper.setAcceleration(50.0);
upperarm_stepper.setMaxSpeed(100);
upperarm_stepper.setAcceleration(50.0);
base_stepper.setCurrentPosition(0);
forearm_stepper.setCurrentPosition(0);
upperarm_stepper.setCurrentPosition(0);
}
void loop() {
// put your main code here, to run repeatedly:
if (Serial.available()>1){
int data = Serial.parseInt();
x=data/100;
y=abs((data-x*100)/10);
z=abs(data%10);
Serial.println(x);
Serial.println(y);
Serial.println(z);
calculate();
Serial.print("basepos= ");Serial.println(basepos);
Serial.print("upperarmpos= ");Serial.println(upperarmpos);
Serial.print("forearmpos= ");Serial.println(forearmpos);
RunCommand(basepos,upperarmpos,forearmpos);
base_stepper.run(); //底座电机运行
forearm_stepper.run(); //后臂电机运行
upperarm_stepper.run(); //前臂电机运行
}
}
void calculate(){
basepos=atan(x/y)*(180/pi)/1.8;
//底角角度
delay(500);
touying=sqrt(pow(x,2)+pow(y,2))-Num;
delay(500);
duanbian=abs(basehigh-z);
xiebian=sqrt(pow(duanbian,2)+pow(touying,2));
upperarmpos1=(acos((pow(upperarm,2)+pow(xiebian,2)-pow(forearm,2))/(2*upperarm*xiebian)))*(180/pi);
if(basehigh==z){
upperarmpos2=0;
}else if(basehigh>z){
upperarmpos2=atan(touying/duanbian)* (180/pi)-90;
}
else if(basehigh<z){
upperarmpos2=atan(duanbian/touying)-90;
}
upperarmpos=(upperarmpos1+upperarmpos2-15)/1.8;
//前臂角度
forearmpos=(acos((pow(upperarm,2)+pow(forearm,2)-pow(xiebian,2))/(2*upperarm*forearm))*(180/pi)+(upperarmpos-90))/1.8;
//后臂角度
}
void RunCommand(int b,int u,int f){
Serial.println("Receive command");
Serial.println(b);
Serial.println(u);
Serial.println(f);
upperarm_stepper.runToNewPosition(u);
delay(100);
forearm_stepper.runToNewPosition(f);
delay(500);
base_stepper.runToNewPosition(b);
delay(500);
}
作为一名机械专业学生,实在不想在代码上花费过多时间(哭笑),没有将两个代码合并,并且本人编程能力很弱,代码中可能有许多错误。
本文章仅供个人学习所用。