Un robot delta controlado por Arduino construido con fischertechnik: robot de recogida y colocación rápido y preciso.
Tal vez pueda interesarte proyectos en arduino, pic, robótica, telecomunicaciones, suscribete en http://www.youtube.com/user/carlosvolt?sub_confirmation=1 mucho videos con código fuentes completos y diagramas
Cosas usadas en este proyecto
Componentes de hardware |
||||||
|
× | 1 | ||||
|
× | 3 | ||||
Aplicaciones de software y servicios en línea. |
||||||
|
||||||
|
||||||
|
Herramientas manuales y máquinas de fabricación. |
|||||
|
Historia
La construcción de robots industriales no significa necesariamente gastar mucho dinero en hardware costoso. Construido con fischertechnik (un juguete de construcción originario de Alemania) y controlado por un Arduino Mega, este robot delta es una máquina bastante simple. Sin embargo, no le falta velocidad ni precisión para cumplir su trabajo: el robot recoge los elementos de una cinta transportadora y los clasifica por color de forma similar a los robots industriales de recogida y colocación.
Delta Robot como robot de pick and place
¿Cuáles son los principales desafíos de este proyecto?
- Cinemática del robot Delta
- Seguimiento de movimiento de artículos en el transportador
- Agarre al vacío
Cinemática del robot Delta
A diferencia de la cinemática simple como la cinemática lineal que a menudo se usa en impresoras 3D, la cinemática del robot delta es más complicada y no es fácil de entender. Para controlar un robot delta con coordenadas cartesianas, se requiere la llamada cinemática inversa. Implementé la cinemática inversa para los robots delta de acuerdo con un artículo publicado por Robert L. Williams II: “El robot paralelo Delta: Soluciones cinemáticas” Aunque esto parece ser computacionalmente costoso, las cinemáticas delta tienen algunas buenas ventajas sobre otras cinemáticas de robots. En primer lugar, son asombrosamente rápidos y precisos, en segundo lugar, tienen un rango de funcionamiento bastante bueno. Sin embargo, las vibraciones son un problema grave y la carga en movimiento debe ser lo más baja posible.
El siguiente video le da una idea de lo que es posible con los robots delta:
Seguimiento de movimiento La posición de cada elemento es capturada por una barrera de luz láser. Esto le permite al robot saber cuándo el artículo ha pasado una cierta posición en el transportador. Además, la velocidad del transportador se mide leyendo una señal del codificador. Esto le permite al robot saber qué tan rápido se mueve el artículo. Dada esa información, el movimiento del robot se puede calcular para que elija el elemento en el momento adecuado.
Pinza de vacío Los artículos son manipulados por una pinza de vacío. Como no tengo una bomba de vacío, he buscado otra solución para esta tarea:
Hay dos cilindros neumáticos montados uno al lado del otro. El primer cilindro está conectado a una válvula que deja entrar o sale la presión. El segundo cilindro está conectado a una ventosa. Cuando se aplica presión al primer cilindro, se extiende. Como ambos pistones están mecánicamente conectados entre sí, el movimiento del primer cilindro también obliga al segundo cilindro a extenderse. Sin embargo, este movimiento genera un vacío dentro del segundo cilindro. Este vacío se utiliza para recoger los artículos.
Piezas personalizadas y cerramiento
Pinza de vacío
Esquemas
Arduino Mega Shield
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 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 |
#include <TimerOne.h> #include <DeltaRobotKinematics.h> #include <MegaDueShield.h> #define LOW_SPEED 50 #define MEDIUM_SPEED 80 #define MAX_SPEED 100 / * Pinza de vacío 1_1 de junio de 2019 - control de presión - velocidad del transportador adaptativo julio 2019 - velocidad del transportador adaptativo julio 2019 pila - filtro de color * / DeltaRobotKinematics delta ; StepperMotor & mot1 = * shield.getStepper ( 2 ) ; // preconfigurado paso a paso StepperMotor & mot2 = * shield.getStepper ( 1); StepperMotor mot3; // half-bridge based stepper motor DCMotor coil31; DCMotor coil32; DCMotor conveyor; DCMotor gripper; DCMotor compressor; DCMotor laser; DCMotor separator; long posM1 = 0; long posM2 = 0; long posM3 = 0; volatile int posConveyor = 0; volatile int pressure; const uint8_t limitSwitch1 = I5; const uint8_t limitSwitch2 = I6; const uint8_t limitSwitch3 = I8; const uint8_t conveyorEncoder = C3; const uint8_t photocell = C4; const uint8_t stack = D4; const uint8_t MPX_pin = I3; const uint8_t colorSensor = I4; const int whiteLowerThreshold = 100; const int whiteUpperThreshold = 175; const int redLowerThreshold = 196; const int redUpperThreshold = 270; const int blueLowerThreshold = 480; const int blueUpperThreshold = 510; bool pass = false; long passTime = 0; uint8_t currentSpeedProfile = LOW_SPEED; void pressureControl() { pressure = analogRead(MPX_pin); if (compressor.getSpeed() < 1) { if (pressure < 140) { compressor.on(); } } else { if (pressure > 187) { compressor.off(); } } } int rad2StepM1(double radian) { return (int) ((radian + 0.785) * 95.51); } int rad2StepM2(double radian) { return (int) ((radian + 0.785) * 127.35); } int rad2StepM3(double radian) { return (int) ((radian + 0.785) * 127.35); } void posP2P(double x, double y, double z) { delta.inverseKinematics(x, y, z); bool t = false; while (!t) { t = mot1.stepping(posM1, rad2StepM1(delta.getPhi2())); t &= mot2.stepping(posM2, rad2StepM2(delta.getPhi3())); t &= mot3.stepping(posM3, rad2StepM3(delta.getPhi1())); } } void posCP(double x1, double y1, double z1, double x2, double y2, double z2) { posP2P(x1, y1, z1); double vect[] = {x2 - x1, y2 - y1, z2 - z1}; double vectLength = sqrt(pow(vect[0], 2) + pow(vect[1], 2) + pow(vect[2], 2)); double unitVect[3]; for (int i = 0; i < 3; i++) { unitVect[i] = vect[i] / vectLength / 2.0; // unitVect: Length 0.5mm } vect[0] = x1; vect[1] = y1; vect[2] = z1; int iterations = vectLength * 2; // equivalent to vectLength / 0.5 for (int i = 0; i < iterations; i++) { vect[0] += unitVect[0]; vect[1] += unitVect[1]; vect[2] += unitVect[2]; posP2P(vect[0], vect[1], vect[2]); } posP2P(x2, y2, z2); } void speedProfile(int profile) { mot1.velocity(profile); mot2.velocity(profile); mot3.velocity(profile); } int colorDetection() { int n = 4; // #of measurements long measurements[n]; for (int i = 0; i < n; i++) { measurements[i] = analogRead(colorSensor); delay(30); } // calc average long avg = 0; for (int i = 0; i < n; i++) { avg += measurements[i]; } avg /= n; // calc error long error = 0; for (int i = 0; i < n; i++) { error += (avg-measurements[i])*(avg-measurements[i]); } Serial.print("Error: "); error /= n; Serial.println(error); if (error < 3) { // measurement accurate, return average Serial.println(avg); return avg; } else { // measurement inaccurate, return 1023 return 1023; } } void referencing() { delay(50); bool ref = false; while (!ref) { ref = mot1.referencing(posM1); ref &= mot2.referencing(posM2); ref &= mot3.referencing(posM3); } delay(50); } // ISR void conveyorISR() { posConveyor++; } void setup() { Serial.begin(115200); Serial.println("Delta Robot @ MegaDueShield"); delta.setUpperLegsLength(75); delta.setLowerLegsLength(180); delta.setBaseSize(41.83); delta.setPlatformSize(26); coil31 = *shield.getDCMotor(5); coil32 = *shield.getDCMotor(6); conveyor = *shield.getDCMotor(1); gripper = *shield.getDCMotor(7); compressor = *shield.getDCMotor(8); laser = *shield.getDCMotor(2); separator = *shield.getDCMotor(4); mot3.setHalfBridge(coil31, coil32); mot1.motorConfig(200, 80, 600, 400); mot2.motorConfig(200, 120, 800, 400); mot3.motorConfig(200, 60, 800, 400); mot1.attachLimitSwitch(limitSwitch1); mot2.attachLimitSwitch(limitSwitch2); mot3.attachLimitSwitch(limitSwitch3); pinMode(photocell, INPUT_PULLUP); pinMode(stack, INPUT_PULLUP); pinMode(conveyorEncoder, INPUT_PULLUP); attachInterrupt(digitalPinToInterrupt(conveyorEncoder), conveyorISR, CHANGE); shield.rgb(0, 0, 150); delay(200); shield.rgbOff(); referencing(); delay(500); speedProfile(80); laser.on(); Timer1.initialize(300000); Timer1.attachInterrupt(pressureControl); } void loop() { mot1.release(); mot2.release(); mot3.release(); while (!digitalRead(stack)) { // no item in stock if (!pass) { conveyor.off(); } else { if ((millis() - passTime) > 2000) { // conveyor on until white item has passed pass = false; } } delay(300); } pass = false; conveyor.cw(135); delay(400); int colorVal = 1023; while (colorVal > 1000) { colorVal= colorDetection(); } // separate separator.on(); delay(80); separator.off(); if (colorVal < whiteUpperThreshold) { // color is white delay(300); pass = true; passTime = millis(); } else { // color is either red or blue, remove item from conveyor delay(20); // wait to prevent light barrier from triggering falsely while (!digitalRead(photocell)) { } posConveyor = 0; long t0 = millis(); while (posConveyor < 140) {} long t1 = millis(); double xTrig = 285.0 - 37940.0 / (t1 - t0); while (posConveyor < xTrig) { } long t = millis(); posP2P(-18, 10, -165); long t2 = millis(); //delay(4000); //posCP(-21, 10, -167, -21, 10, -176); posP2P(-18, 10, -176); long t3 = millis(); gripper.on(); delay(200); // choose where to place the item based on color if (colorVal < blueLowerThreshold) { // color is red posP2P(0, 0, -160); posP2P(60, 0, -160); } else { // color is blue posP2P(-20, 30, -160); posP2P(-70, -20, -160); } gripper.off () ; retraso ( 300 ) ; posP2P ( 0 , 0 , -140 ) ; referenciando () ; } } |
Fuente
SUSCRIBETE A NUESTROS BOLETINES, RECIBE EN TU CORREO LAS NOTICIAS MÁS DESTACADAS, SÓLO INGRESANDO TU CORREO ELECTRÓNICO
[wysija_form id=”1″]
VIDEO RECOMENDADO