3自由度串联机械臂实现电磁铁搬运功能
本帖最后由 机器谱Robotway 于 2023-3-13 09:56 编辑1、功能描述
R308样机是一款拥有3自由度的串联机械臂。本文提供的示例所实现的功能为:在3自由度串联机械臂样机上安装电磁铁,实现电磁铁搬运物品的功能。https://28846868.s21i.faiusr.com/4/ABUIABAEGAAg5oq2nwYo1srh7gEwmQY4mwY!300x300.png.webphttps://28846868.s21i.faiusr.com/3/ABUIABADGAAglOjQnwYo4NedvQUwsAQ4uwI.gif.webp
2、电子硬件在这个示例中,我们采用了以下硬件,请大家参考:
主控板Basra(兼容Arduino Uno)
扩展板Bigfish2.1
舵机270°伺服电机
电池7.4V锂电池
其它
电磁铁、USB线
电路连接说明:
https://28846868.s21i.faiusr.com/4/ABUIABAEGAAg3_jQnwYowKLPFTDIBjiUBg!500x500.png.webp注:① 270°伺服电机连接在Bigfish扩展板D4 . GND . VCC接口上② 270°伺服电机连接在Bigfish扩展板D7 . GND . VCC接口上③ 270°伺服电机连接在Bigfish扩展板D11 . GND . VCC接口上电磁铁连接在Bigfish扩展板D9,D10接口上
3、运动控制上位机:Controller 1.0下位机编程环境:Arduino 1.8.19
3.1初始位置的设定① 将Controller下位机程序servo_bigfish.ino直接下载到主控板。这段代码供Controller上位机与主控板通信,并允许调试舵机。代码如下:/*------------------------------------------------------------------------------------
版权说明: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-01-31 https://www.robotway.com/
------------------------------
/*
* Bigfish扩展板舵机口; 4, 7, 11, 3, 8, 12, 14, 15, 16, 17, 18, 19
* 使用软件调节舵机时请拖拽对应序号的控制块
*/
#include <Servo.h>
#define ANGLE_VALUE_MIN 0
#define ANGLE_VALUE_MAX 180
#define PWM_VALUE_MIN 500
#define PWM_VALUE_MAX 2500
#define SERVO_NUM 12
Servo myServo;
int data_array = {0,0}; //servo_pin: data_array, servo_value: data_array;
int servo_port = {4, 7, 11, 3, 8, 12, 14, 15, 16, 17, 18, 19};
int servo_value = {};
String data = "";
boolean dataComplete = false;
void setup() {
Serial.begin(9600);
}
void loop() {
while(Serial.available())
{
int B_flag, P_flag, T_flag;
data = Serial.readStringUntil('\n');
data.trim();
for(int i=0;i<data.length();i++)
{
//Serial.println(data);
switch(data)
{
case '#':
B_flag = i;
break;
case 'P':
{
String pin = "";
P_flag = i;
for(int i=B_flag+1;i<P_flag;i++)
{
pin+=data;
}
data_array = pin.toInt();
}
break;
case 'T':
{
String angle = "";
T_flag = i;
for(int i=P_flag+1;i<T_flag;i++)
{
angle += data;
}
data_array = angle.toInt();
servo_value)] = data_array;
}
break;
default: break;
}
}
/*
Serial.println(B_flag);
Serial.println(P_flag);
Serial.println(T_flag);
for(int i=0;i<2;i++)
{
Serial.println(data_array);
}
*/
dataComplete = true;
}
if(dataComplete)
{
for(int i=0;i<SERVO_NUM;i++)
{
ServoGo(i, servo_value);
/*********************************串口查看输出***********************************/
// Serial.print(servo_value);
// Serial.print(" ");
}
// Serial.println();
/*********************************++++++++++++***********************************/
dataComplete = false;
}
}
void ServoStart(int which){
if(!myServo.attached() && (servo_value != 0))myServo.attach(servo_port);
else return;
pinMode(servo_port, OUTPUT);
}
void ServoStop(int which){
myServo.detach();
digitalWrite(servo_port,LOW);
}
void ServoGo(int which , int where){
ServoStart(which);
if(where >= ANGLE_VALUE_MIN && where <= ANGLE_VALUE_MAX)
{
myServo.write(where);
}
else if(where >= PWM_VALUE_MIN && where <= PWM_VALUE_MAX)
{
myServo.writeMicroseconds(where);
}
}
int pin2index(int _pin){
int index;
switch(_pin)
{
case 4: index = 0; break;
case 7: index = 1; break;
case 11: index = 2; break;
case 3: index = 3; break;
case 8: index = 4; break;
case 12: index = 5; break;
case 14: index = 6; break;
case 15: index = 7; break;
case 16: index = 8; break;
case 17: index = 9; break;
case 18: index = 10; break;
case 19: index = 11; break;
}
return index;
}
下载完成后,保持主控板和电脑的USB连接,以便利用上位机进行调试。② 双击打开Controller 1.0b.exe:
https://28846868.s21i.faiusr.com/4/ABUIABAEGAAggevQnwYo6uOqrwIwywI4nAI.png.webp
https://28846868.s21i.faiusr.com/4/ABUIABAEGAAgluvQnwYosZzUrwYwqgg46AU!600x600.png.webp
③ 界面左上角选择:设置-面板设置,弹出需要显示的调试块,可通过勾选隐藏不需要调试的舵机块:联机-选择主控板对应端口号以及波特率。
https://28846868.s21i.faiusr.com/4/ABUIABAEGAAgvOvQnwYo2uWxlgIwuAg47gU!600x600.png.webphttps://28846868.s21i.faiusr.com/4/ABUIABAEGAAgyuvQnwYogJD_3gQwuAg47gU!600x600.png.webphttps://28846868.s21i.faiusr.com/4/ABUIABAEGAAg1_vQnwYo193r_QMwuAg47gU!600x600.png.webphttps://28846868.s21i.faiusr.com/4/ABUIABAEGAAg4_vQnwYo_pis4gUwuAg47gU!600x600.png.webp
④ 拖动进度条,可以观察相应的舵机角度转动。写好对应的舵机调试角度,勾选左下角添加-转化,获得舵机调试的数组:
https://28846868.s21i.faiusr.com/4/ABUIABAEGAAgg_zQnwYov56W0wcwuAg47gU!600x600.png.webp
⑤ 将该数组直接复制到相应的Arduino程序中的get_coordinate()部分进行使用。
3.2调试好角度后将电磁铁搬运例程(calculate_angle_test.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 机器谱 2023-01-31 https://www.robotway.com/
------------------------------*/
#include <math.h>
#include <Servo.h>
#define SERVO_SPEED 3460 //定义舵机转动快慢的时间
#define ACTION_DELAY 200 //定义所有舵机每个状态时间间隔
#define L1 172
#define L2 160
#define L3 135
Servo myServo;
int f = 200; //定义舵机每个状态间转动的次数,以此来确定每个舵机每次转动的角度
int servo_port = {4,7,11,3,8,12}; //定义舵机引脚
int servo_num = sizeof(servo_port) / sizeof(servo_port); //定义舵机数量
float value_init = {1500, 1500, 1500, 0, 0, 0}; //定义舵机初始角度
double theta = {};
float value_pwm = {};
float coordinate = {};
int data_num;
boolean dataComplete = false;
void setup() {
Serial.begin(9600);
pinMode(9, OUTPUT);
pinMode(10, OUTPUT);
for(int i=0;i<servo_num;i++){
ServoGo(i,value_init);
}
get_coordinate(160, 0, 45);
delay(1000);
}
void loop() {
get_coordinate(125, 100, 45);
get_coordinate(125, 100, 20);
delay(1000);
put();
get_coordinate(125, 100, 45);
get_coordinate(125, 100, 20);
delay(500);
get();
get_coordinate(125, 100, 45);
get_coordinate(158, 5, 80);
get_coordinate(158, 5, 51);
delay(1000);
put();
get_coordinate(158, 5, 80);
get_coordinate(158, 5, 51);
delay(500);
get();
get_coordinate(110, 0, 158);
get_coordinate(100, -80, 116);
delay(1000);
put();
get_coordinate(100, -80, 140);
get_coordinate(100, -80, 116);
delay(500);
get();
get_coordinate(100, -80, 140);
get_coordinate(110, 0, 160);
get_coordinate(158, 5, 51);
delay(1000);
put();
get_coordinate(158, 5, 80);
get_coordinate(158, 5, 51);
delay(500);
get();
get_coordinate(160, 5, 80);
delay(200);
}
void get_coordinate(float x, float y, float z){
coordinate = x;
coordinate = y;
coordinate = z;
angle();
}
void angle(){
calculate_position(coordinate);
for(byte i=0;i<3;i++){
value_pwm = map(theta, 0, 180, 500, 2500);
}
servo_move(value_pwm, value_pwm, value_pwm, 0, 0, 0);
dataComplete = false;
}
void calculate_position(float coordinate){
float a, b, c, posX, posY, posZ;
double theta0, theta1, theta2;
a = L2;
b = L3;
posX = coordinate == 0 ? 1 : coordinate;
posY = coordinate;
posZ = coordinate;
theta0 = atan(posX / posY);
c = sqrt(posX * posX / sq(sin(theta0)) + sq(posZ - L1));
theta2 = acos((a * a + b * b - c * c) / (2 * a * b));
theta1 = asin((posZ - L1) / c) + acos((a * a + c * c - b * b) / (2 * a * c));
if(theta0 >= 0){
theta = theta0 * 180 / PI;
}
else
{
theta = 180 + theta0 * 180 / PI;
}
theta = 90 - theta1 * 180 / PI;
theta = theta2 * 180 / PI;
// Serial.print("theta0 = ");
// Serial.println(theta);
// Serial.print("theta1 = ");
// Serial.println(theta);
// Serial.print("theta2 = ");
// Serial.println(theta);
// Serial.println("-------------------------------------");
}
void ServoStart(int which)
{
if(!myServo.attached())myServo.attach(servo_port);
pinMode(servo_port, OUTPUT);
}
void ServoStop(int which)
{
myServo.detach();
digitalWrite(servo_port,LOW);
}
void ServoGo(int which , int where)
{
if(where!=200)
{
if(where==201) ServoStop(which);
else
{
ServoStart(which);
myServo.writeMicroseconds(where);
}
}
}
void servo_move(float value0, float value1, float value2, float value3, float value4, float value5)
{
float value_arguments[] = {value0, value1, value2, value3, value4, value5};
float value_delta;
for(int i=0;i<servo_num;i++)
{
value_delta = (value_arguments - value_init) / f;
}
for(int i=0;i<f;i++)
{
for(int k=0;k<servo_num;k++)
{
value_init = value_delta == 0 ? value_arguments : value_init + value_delta;
}
for(int j=0;j<servo_num;j++)
{
ServoGo(j,value_init);
}
delayMicroseconds(SERVO_SPEED);
}
}
void get(){
digitalWrite(9, HIGH);
digitalWrite(10, LOW);
delay(1000);
}
void put(){
digitalWrite(9, LOW);
digitalWrite(10, LOW);
delay(1000);
}
4. 资料下载
资料内容:
①R308-电磁铁搬运-程序源代码
②R308-电磁铁搬运-样机3D文件
③Controller1.0b资料包
资料下载地址:https://www.robotway.com/h-col-191.html
想了解更多机器人开源项目资料请关注 机器谱网站 https://www.robotway.com
页:
[1]