คำอธิบาย
แขนกลจับชิ้นงาน Linear Slide Mechanical Arm เพื่อการทดลองและเรียนรู้ ประยุกต์ใช้งานแขนกลจับชิ้นงาน
การทำงาน
- เริ่มจาก เซนเซอร์โฟโตอิเล็คทริคอินฟราเรด Infrared Photoelectric Sensors ตรวจจับขวดน้ำ
- จากนั้น แขน ที่ติดตั้งมือจับ Gripper เซอร์โวมอเตอร์ 500g ซึ่งแขนนั้นติดตั้งบนรางสไลด์ยาว 1 เมตร
- ขับเคลื่อนด้วยสเต็ปปิ้งมอเตอร์ สไลด์เพื่อนำพาชิ้นงานจากจุดต้นทางไปยังปลายทาง
- การยกแขนกระทำด้วยเซอร์โวมอเตอร์ High torque 110Kg.cm
- มือจับ Gripper จับขวด ประกอบด้วย เซอร์โวมอเตอร์ 500g
- ควบคุมการทำงานทั้งหมดด้วยบอร์ด Arduino
มีอะไรเตรียมไว้ให้ในชุด
- รางสไลด์ยาว 1 เมตร พร้อมสเต็ปมอเตอร์
- เซอร์โวมอเตอร์ High Torque 110Kg Cm สำหรับ ยกแขน
- ชุดมือจับชิ้นงาน Gripper 4 พร้อมเซอร์โวมอเตอร์ MT0601 เซอร์โวมอเตอร์ แรงบิดสูง Digital High Torque RC Servo Motor 20kg 180D TD-8120MG
- ชุดควบคุม Arduino + Shield + Driver A4988
- เซนเซอร์ตรวจจับวัตถุ โฟโตอิเล็กทริกแบบอินฟราเรด Photoelectric
- สวิตชิ่งพาวเวอร์ซัพพลาย +5VDC, +12VDC
Source Code // Test Step Motor
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 |
#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 V1.1
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 |
#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 = 9; int buttonState = 0; char OK_flag=0; int State=0; int MaxDistance = 4200; const int Gripper_servo = 13; // มือจับ const int Arm_servo = 12; // แขน char arm_Up = 50;// ตำแหน่งยกแขนขึ้น char arm_Down = 80;// ตำแหน่งวางแขนลง char Gripper_ON = 100; // มือจับ char Gripper_OFF = 50; // ปล่อยมือ int SensorA6=0; // เซนเซอร์ตรวจจับขวดว่ามีหรือไม่ void setup() { pinMode(8, OUTPUT); digitalWrite(8,LOW);// enable pinMode(A6, INPUT_PULLUP );//เซนเซอร์ stepper.setMaxSpeed(1000.0); //ปรับความเร็ว stepper.setAcceleration(2000.0); pinMode(HomeSW,INPUT_PULLUP); MyGripper.attach(Gripper_servo); // attaches the servo on pin 9 to the servo object MyARM.attach(Arm_servo); // attaches the servo on pin 9 to the servo object stepper.setCurrentPosition(MaxDistance); //stepper.runToNewPosition(0); Serial.begin(9600); } void loop() { //Serial.print("\t State = "); //Serial.println(State); switch (State) { case 0: // เคลื่อนเข้า home มอเตอร์แกนนอน มอเตอร์1 // อ่านค่าสวิตช์ Home buttonState = digitalRead(HomeSW); if (buttonState == HIGH) { stepper.setSpeed(-500); stepper.runSpeed(); MyARM.write(arm_Up);//ยกแขน90องศา MyGripper.write(50);//ปล่อยมือ } else //ชนสวิตช์3 ให้หยุดมอเตอร์ { stepper.stop(); stepper.setCurrentPosition(0);// set Zero stepper.moveTo(4200); stepper.setMaxSpeed(1200); stepper.setAcceleration(1200); State = 10; } break; case 10: //เคลื่อนไปจนสุด4200 { 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: // วางแขนลง แล้วจับของ { MyARM.write(arm_Down);//วางแขน //MyGripper.write(100);//มือจับ 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: // ยกแขนขึ้น { MyARM.write(arm_Up);//ยกแขน90องศา State = 25; } break; case 25: // หน่วงเวลา { delay(1000); State = 30; } break; case 30: // เคลื่อนเข้า home แกนตั้ง มอเตอร์3 { stepper.moveTo(200); stepper.setMaxSpeed(1200); 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: // วางแขนลง { MyARM.write(arm_Down); 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: // ปล่อยมือ { MyARM.write(arm_Up);//ยกแขน90องศา State = 49; } break; case 49: // หน่วงเวลา { delay(1000); State = 50; } break; case 50: { //MyARM.write(arm_Up);//ยกแขน90องศา stepper.moveTo(4200); stepper.setMaxSpeed(1200); stepper.setAcceleration(1200); State = 10; } } } |
รีวิว
ยังไม่มีบทวิจารณ์