คำอธิบาย
แขนกลจับชิ้นงาน Linear Slide Mechanical Arm เพื่อการทดลองและเรียนรู้ ประยุกต์ใช้งานแขนกลจับชิ้นงาน
การทำงาน
- เริ่มจาก เซนเซอร์โฟโตอิเล็คทริคอินฟราเรด Infrared Photoelectric Sensors ตรวจจับขวดน้ำ
- จากนั้น แขน ที่ติดตั้งมือจับ Gripper เซอร์โวมอเตอร์ 500g ซึ่งแขนนั้นติดตั้งบนรางสไลด์ยาว 1 เมตร
- ขับเคลื่อนด้วยสเต็ปปิ้งมอเตอร์ สไลด์เพื่อนำพาชิ้นงานจากจุดต้นทางไปยังปลายทาง
- การยกแขนกระทำด้วยเซอร์โวมอเตอร์ High torque 110Kg.cm
- มือจับ Gripper จับขวด ประกอบด้วย เซอร์โวมอเตอร์ 500g
- ควบคุมการทำงานทั้งหมดด้วยบอร์ด Arduino
ในชุดประกอบด้วย
- รางสไลด์ยาว 1 เมตร พร้อมสเต็ปมอเตอร์ Nema17
- เซอร์โวมอเตอร์ High Torque 110Kg.cm สำหรับยกแขน
- ชุดมือจับชิ้นงาน Gripper C พร้อมเซอร์โวมอเตอร์ 500g
- ชุดควบคุม Arduino Shield + Driver A4988
- เซนเซอร์โฟโตอิเล็คทริคอินฟราเรด Infrared Photoelectric Sensors
- สวิตชิ่งพาวเวอร์ซัพพลาย DC12V
- ลิมิตสวิตช์พร้อมสาย Limit Switch
Source Code // Test Step Motor
#include <AccelStepper.h>
AccelStepper stepper(AccelStepper::DRIVER, 2, 5);
// pin 2 = Step
// pin 5 = Dir
void setup()
{
pinMode(8, OUTPUT);
digitalWrite(8,LOW);// enable
stepper.setMaxSpeed(1000);
stepper.setSpeed(500);
}
void loop()
{
stepper.runSpeed();
}
Source Code Linear Slide Mechanical Arm Gripper Robot V3
#include <AccelStepper.h>
#include <Servo.h>
Servo MyGripper; // create servo object to control a servo
Servo MyARM; // create servo object to control a servo
// Define a stepper and the pins it will use
AccelStepper stepper(AccelStepper::DRIVER, 5, 2);
const int HomeSW = A7;
int buttonState = 0;
char OK_flag = 0;
int State = 0;
int MaxDistance = 3000; //ระยะที่วิ่งจากจุด Home จุดจับวัตถุ
int MinDistance = 200; // จุดปล่อยวัตถุ
int MotorSpeed = 1100; //ปรับความเร็วมอเตอร์
const int Gripper_servo = 13; // มือจับ
const int Arm_servo = 12; // แขน
int arm_Up = 75; // ตำแหน่งยกแขนขึ้น (หน่วย องศา)
int arm_Down = 55; // ตำแหน่งวางแขนลง (หน่วย องศา)
int Gripper_ON = 180; // มือจับ (หน่วย องศา)
int Gripper_OFF = 90; // ปล่อยมือ (หน่วย องศา)
int SensorA6 = 0; // เซนเซอร์ตรวจจับขวดว่ามีหรือไม่
int pos = 0;
int SetSpeedArm = 100; // หน่วยเป็น mSec , 100mSec 0.1sec
void setup(){
// สเต็ปมอเตอร์
pinMode(8, OUTPUT);
digitalWrite(8,LOW); // enable
stepper.setMaxSpeed(MotorSpeed);
stepper.setAcceleration(2000.0);
MyGripper.attach(Gripper_servo); // attaches the servo on pin 13 to the servo object
MyARM.attach(Arm_servo); // attaches the servo on pin 12 to the servo object
stepper.setCurrentPosition(MaxDistance);
MyARM.write(arm_Up);
delay(100);
Serial.begin(9600);
for (pos = Gripper_OFF; pos >= Gripper_ON; pos -= 1)
{
// in steps of 1 degree
MyGripper.write(pos); // tell servo to go to position in variable 'pos'
delay(30); // waits 15ms for the servo to reach the position
}
MyARM.write(arm_Up);
delay(100);
for (pos = arm_Down; pos <= arm_Up; pos += 1)
{
// in steps of 1 degree
MyARM.write(pos); // tell servo to go to position in variable 'pos'
delay(30); // waits mSec for the servo to reach the position
}
delay(100);
}
void loop(){
//buttonState = analogRead(HomeSW);
//Serial.print("State = ");
//Serial.println(State);
switch (State)
{
case 0: // เคลื่อนเข้า home
// อ่านค่าสวิตช์ Home ยังไม่ชน อ่านค่าได้ 1023 ที่ 5V
buttonState = analogRead(HomeSW);
if (buttonState >= 1000)
{
stepper.setSpeed(-500);
stepper.runSpeed();
MyARM.write(arm_Up);//ยกแขน90องศา
MyGripper.write(Gripper_OFF);//ปล่อยมือ
}
else if (buttonState <= 10) //ชนสวิตช์อ่านค่าได้ 0 ให้หยุดมอเตอร์
{
stepper.stop();
stepper.setCurrentPosition(0);// set Zero
stepper.moveTo(MaxDistance); //ความเร็วมอเตอร์ตอนวิ่งไปจับวัตถุ
stepper.setMaxSpeed(MotorSpeed); //ความเร็วมอเตอร์
stepper.setAcceleration(1200);// ความเร่ง
State = 10;
delay(300);
buttonState = digitalRead(HomeSW);
if (buttonState == HIGH)
{
State = 0;// home again
}
else
{
State = 10;
}
}
break;
case 10: //เคลื่อนไปจนสุด2000
{
if (stepper.distanceToGo() == 0)
{
stepper.moveTo(-stepper.currentPosition());
State = 15;
}
stepper.run();
}
break;
case 15: // เช็คเซนเซอร์ตำแหน่งขวด ว่ามีหรือไม่
{
SensorA6 = analogRead(A6);
if (SensorA6 < 200)
{
State = 16;
Serial.print("\t SensorA6 = ");
Serial.println(SensorA6);
}
}
break;
case 16: // หน่วงเวลา
{
delay(1000);
State = 20;
}
break;
case 20: // วางแขนลง แล้วจับของ
{
//ค่อยๆ วางแขน
for (pos = arm_Up; pos >= arm_Down; pos -= 1)
{ // goes from 0 degrees to 180 degrees
// in steps of 1 degree
MyARM.write(pos); // tell servo to go to position in variable 'pos'
delay(SetSpeedArm); // waits 15ms for the servo to reach the position
}
State = 21;
}
break;
case 21: // หน่วงเวลา
{
delay(1000);
State = 22;
}
break;
case 22: // จับของ
{
MyGripper.write(Gripper_ON);//มือจับ
State = 23;
}
break;
case 23: // หน่วงเวลา
{
delay(1000);
State = 24;
}
break;
case 24: // ยกแขนขึ้น
{
//ค่อยๆ ยกแขน90องศา
for (pos = arm_Down; pos <= arm_Up; pos += 1)
{ // goes from 0 degrees to 180 degrees
// in steps of 1 degree
MyARM.write(pos); // tell servo to go to position in variable 'pos'
delay(SetSpeedArm); // waits 15ms for the servo to reach the position
}
State = 25;
}
break;
case 25: // หน่วงเวลา
{
delay(500);
State = 30;
}
break;
case 30: // เคลื่อนเข้า home แกนตั้ง มอเตอร์3
{
stepper.moveTo(MinDistance);
stepper.setMaxSpeed(MotorSpeed);
stepper.setAcceleration(1200);
State = 31;
}
break;
case 31: // เคลื่อนเข้า home แกนตั้ง มอเตอร์3
{
if (stepper.distanceToGo() == 0)
{
stepper.moveTo(-stepper.currentPosition());
State = 40;
}
stepper.run();
}
break;
case 40: // วางแขนลง
{
//ค่อยๆ วางแขน
for (pos = arm_Up; pos >= arm_Down; pos -= 1)
{ // goes from 0 degrees to 180 degrees
// in steps of 1 degree
MyARM.write(pos); // tell servo to go to position in variable 'pos'
delay(SetSpeedArm); // waits 15ms for the servo to reach the position
}
State = 45;
}
break;
case 45: // หน่วงเวลา
{
delay(1000);
State = 46;
}
break;
case 46: // ปล่อยมือ
{
MyGripper.write(Gripper_OFF);//มือปล่อย
State = 47;
}
break;
case 47: // หน่วงเวลา
{
delay(1000);
State = 48;
}
break;
case 48: // ปล่อยมือ
{
//ค่อยๆ ยกแขน90องศา
for (pos = arm_Down; pos <= arm_Up; pos += 1)
{ // goes from 0 degrees to 180 degrees
// in steps of 1 degree
MyARM.write(pos); // tell servo to go to position in variable 'pos'
delay(SetSpeedArm); // waits 15ms for the servo to reach the position
}
State = 49;
}
break;
case 49: // หน่วงเวลา
{
delay(1000);
State = 50;
}
break;
case 50:
{
stepper.moveTo(MaxDistance);
stepper.setMaxSpeed(MotorSpeed);
stepper.setAcceleration(1200);
State = 10;
}
}
}
Wiring





รีวิว
ยังไม่มีบทวิจารณ์