Caso práctico: Hexápodo Arduino Mega 2560 + PCA9685 + XBee

Caso práctico: Hexápodo Arduino Mega 2560 + PCA9685 + XBee — hero

Objetivo y caso de uso

Qué construirás: Un robot hexápodo controlado por Zigbee utilizando Arduino Mega 2560, PCA9685 y XBee S2C.

Para qué sirve

  • Control remoto de un hexápodo para exploración en terrenos difíciles.
  • Implementación de evitación de obstáculos utilizando el sensor VL53L0X.
  • Demostraciones de robótica educativa en ferias tecnológicas.
  • Proyectos de investigación en movilidad robótica y comunicación inalámbrica.

Resultado esperado

  • Latencia de control remoto inferior a 100 ms.
  • Capacidad de respuesta a comandos en tiempo real con un mínimo de 10 FPS.
  • Precisión de detección de obstáculos de hasta 30 cm con el sensor ToF.
  • Consumo de energía del sistema menor a 500 mA durante la operación.

Público objetivo: Estudiantes avanzados y entusiastas de la robótica; Nivel: Avanzado

Arquitectura/flujo: Arduino Mega 2560 controla el PCA9685 para manejar los servos, mientras que el XBee S2C se encarga de la comunicación Zigbee y el VL53L0X proporciona datos de distancia para la evitación de obstáculos.

Nivel: Avanzado

Prerrequisitos

  • Sistema operativo recomendado:
  • Ubuntu 22.04.4 LTS (64-bit) o equivalente en Linux con soporte para USB CDC.
  • Alternativa: Windows 10/11 o macOS 12+, con adaptaciones de puerto serie.

  • Toolchain exacta (probada):

  • Arduino CLI 0.35.3
  • Core Arduino AVR Boards arduino:avr@1.8.6
  • avr-gcc 7.3.0-atmel3.6.1
  • avrdude 6.3
  • Bibliotecas Arduino (Arduino Library Manager):
  • Adafruit PWM Servo Driver Library@2.4.1
  • Adafruit BusIO@1.14.5
  • Adafruit Unified Sensor@1.1.14
  • Adafruit VL53L0X@1.3.1
  • Python 3.10.12 (opcional, para script de comandos por ZigBee)
  • minicom 2.7.1 (o picocom) para terminal serie en Linux, o PuTTY en Windows

  • Hardware principal del caso:

  • Arduino Mega 2560
  • PCA9685 (driver 16 canales servo por I2C)
  • XBee S2C (Zigbee) en modo transparente (AP=0)
  • VL53L0X (sensor ToF por I2C)
  • Objetivo del proyecto: servo-hexapod-zigbee (hexápodo de 18 servos con control remoto Zigbee y evitación de obstáculos con ToF).

  • Notas de compatibilidad:

  • Arduino Mega 2560 usa 5 V lógicos; el XBee S2C opera a 3.3 V. Es obligatorio un shield con conversión de nivel o un conversor bidireccional (TX/RX).
  • PCA9685 y VL53L0X comparten el bus I2C (SDA/SCL); asegúrate de que sus direcciones no colisionen (por defecto PCA9685 0x40, VL53L0X 0x29).

Materiales

  • Electrónica y módulos:
  • 1x Arduino Mega 2560 (original o compatible, con USB).
  • 1x PCA9685 16-channel 12-bit PWM Servo Driver (dirección por defecto 0x40).
  • 1x XBee S2C Zigbee (serie S2C, 2.4 GHz).
  • 1x Shield/adaptador XBee para Arduino Mega (con conversión de nivel a 3.3 V) o conversor de nivel bidireccional para UART.
  • 1x VL53L0X (módulo ToF, 940 nm).
  • 18x servos estándar para robótica (ej.: SG90/MG90S para prototipo o servos metálicos 12–20 kg·cm para carga real).
  • 1x Fuente DC 6V–7.4 V con capacidad ≥ 5–10 A (según servos).
  • 1x Portapilas LiPo 2S/3S o fuente conmutada 6 V regulada de alta corriente.
  • Cableado Dupont, regletas, tornillería y bridas.
  • 1x Chasis de hexápodo (6 patas, 3 DOF por pata: coxa, fémur, tibia).
  • 1x Fusible/limitador o protector de corriente para la línea de servos (recomendado).
  • 1x Interruptor general en el bus de servos (recomendado).

  • Opcionales útiles:

  • 1x Módulo UBEC 5 V/6 V de 5–10 A para servos.
  • Pasta térmica/adhesivo para disipación del PCA9685 (no siempre necesario, pero útil).

  • Software:

  • Arduino CLI 0.35.3 (instalar por script oficial).
  • Librerías especificadas (vías Arduino CLI).
  • minicom/picocom o Python para pruebas Zigbee.

Preparación y conexión

Consideraciones eléctricas

  • Los servos NO deben alimentarse desde el pin 5V del Arduino Mega. Usa una fuente externa para la línea V+ del PCA9685 (pines “V+” de potencia).
  • Une siempre GND del Arduino, GND del PCA9685 y GND de la fuente de servos. Masa común es imprescindible para estabilidad y PWM correcto.
  • El XBee S2C debe recibir 3.3 V y señales TX/RX a 3.3 V. Emplea un shield XBee o conversores de nivel. No conectes el XBee directamente a 5 V.

Mapeo de pines/puertos

  • I2C en Arduino Mega 2560:
  • SDA: pin 20
  • SCL: pin 21

  • UART para XBee:

  • Serial1: RX1 pin 19, TX1 pin 18 (recomendado para dejar Serial0/USB para logs).

  • Alimentación:

  • PCA9685: VCC a 5 V del Mega (lógica), GND común; V+ (poder) a 6 V–7.4 V externa para servos.
  • VL53L0X: VCC a 5 V si el módulo tiene regulador/level shifting (común en breakout comerciales), o 3.3 V si es bare.

Tabla de conexiones

Módulo Pin/Señal módulo Conecta a (Mega/otro) Notas
PCA9685 VCC 5V Mega Lógica
PCA9685 GND GND común Común a todo
PCA9685 SDA SDA (20) Mega I2C
PCA9685 SCL SCL (21) Mega I2C
PCA9685 V+ (barral) +6–7.4 V externa Potencia servos
PCA9685 GND (barral) GND fuente servos Común
VL53L0X VCC 5V (si trae regulador) Ver ficha módulo
VL53L0X GND GND común
VL53L0X SDA SDA (20) Mega I2C
VL53L0X SCL SCL (21) Mega I2C
XBee S2C VCC 3.3 V del shield No 5 V
XBee S2C GND GND común
XBee S2C DOUT (TX del XBee) RX1 (19) Mega (via shield/level) UART
XBee S2C DIN (RX del XBee) TX1 (18) Mega (via shield/level) UART
Servos (18) Señal Canales PCA9685 0–17 Ver mapeo abajo
Servos +V V+ PCA9685 6–7.4 V
Servos GND GND PCA9685

Mapeo de servos a canales (hexápodo 6 patas x 3 DOF)

  • Convención de patas: L0, L1, L2 (lado izquierdo front–middle–rear), R0, R1, R2 (lado derecho front–middle–rear).
  • DOF por pata: coxa (rotación horizontal), fémur (levanta/baja), tibia (extiende).
Pata Coxa (canal) Fémur (canal) Tibia (canal)
L0 0 1 2
L1 3 4 5
L2 6 7 8
R0 9 10 11
R1 12 13 14
R2 15 16 17
  • Ajusta los canales si tu cableado físico difiere, pero mantén una estructura coherente para simplificar el control y las gait tables.

Configuración básica del XBee S2C (modo transparente)

  • Conecta el XBee remoto a tu PC por un adaptador USB-XBee (3.3 V).
  • Entra en modo de comandos “AT” a 115200 bps (por defecto puede venir a 9600 bps; ajusta según sea necesario):
  • Abre minicom/picocom: a 9600 o 115200 según módulo.
  • Teclea “+++” y espera “OK”.
  • Configura (ejemplo: PAN en 0x1234, canal C, router/coordinator según topología). Para control remoto simple, haz que el robot sea “Router” (CE=0) y el XBee de la PC “Coordinator” (CE=1):
  • ATRE
  • ATAP0 (modo transparente)
  • ATBD7 (115200 bps)
  • ATCE1 (coordinator en el remoto de PC) o ATCE0 (router en el robot)
  • ATID1234 (PAN ID)
  • ATCH0C (canal 0x0C, opcional)
  • ATWR (guardar)
  • ATCN (salir)
  • En el lado del robot (XBee en el shield del Mega), aplica:
  • ATAP0
  • ATBD7
  • ATCE0
  • ATID1234
  • ATWR
  • Nota: si prefieres API mode (AP=2), modifica el código para usar frames; en este caso práctico usamos transparente para mantener el enfoque en gait + sensórica.

Código completo (Arduino C++)

El siguiente sketch controla:
– PCA9685 a 50 Hz para 18 servos.
– Gait tipo “trípode” con temporización no bloqueante.
– Parser de comandos por Zigbee (Serial1) con texto: FWD, BACK, LEFT, RIGHT, STOP, STEP, SPEED n, CALIB leg dof offset.
– VL53L0X para evitación: detiene y notifica si hay obstáculo < 200 mm.

Guarda el archivo como servo_hexapod_zigbee/servo_hexapod_zigbee.ino.

#include <Wire.h>
#include <Adafruit_PWMServoDriver.h>
#include <Adafruit_VL53L0X.h>
#include <Adafruit_Sensor.h>

// ---------- Configuración PCA9685 ----------
static const uint8_t PCA_ADDR = 0x40;
static const float SERVO_FREQ = 50.0f;     // Hz

Adafruit_PWMServoDriver pca = Adafruit_PWMServoDriver(PCA_ADDR);

// Rango típico de servo en microsegundos:
static const int SERVO_MIN_US = 500;
static const int SERVO_MAX_US = 2500;

// Canales por pata (coxa, femur, tibia)
struct LegMap { uint8_t coxa, femur, tibia; };
LegMap legs[6] = {
  {0, 1, 2},     // L0
  {3, 4, 5},     // L1
  {6, 7, 8},     // L2
  {9, 10, 11},   // R0
  {12, 13, 14},  // R1
  {15, 16, 17}   // R2
};

// Offsets por servo para centrado (us). Ajusta tras calibración.
int16_t servoOffsetUs[18] = {
  0,0,0,  0,0,0,  0,0,0,  0,0,0,  0,0,0,  0,0,0
};

// Inversión por servo (1 normal, -1 invertido)
int8_t servoDir[18] = {
  1, -1, -1,   // L0: coxa normal, femur invertido, tibia invertida
  1, -1, -1,   // L1
  1, -1, -1,   // L2
  -1, -1, -1,  // R0: coxa invertida (simetría), femur invertido, tibia invertida
  -1, -1, -1,  // R1
  -1, -1, -1   // R2
};

// ---------- Cinemática sencilla (3 DOF por pata) ----------
struct Vec3 { float x, y, z; };

// Longitudes (mm) de cada link. Ajusta a tu chasis.
static const float L_COXA = 28.0f;
static const float L_FEMUR = 55.0f;
static const float L_TIBIA = 85.0f;

// Límites de ángulo por DOF (grados)
static const float COXA_MIN = -45.0f, COXA_MAX = 45.0f;
static const float FEMUR_MIN = -20.0f, FEMUR_MAX = 75.0f;
static const float TIBIA_MIN = -70.0f, TIBIA_MAX = 20.0f;

// Conversión de ángulo (grados) a microsegundos
int angleToUs(float angleDeg) {
  // Mapear [0..180] a [SERVO_MIN_US..SERVO_MAX_US]
  // Primero acotamos a 0..180 desde una referencia 90 en neutro
  float a = angleDeg;
  if (a < 0) a = 0;
  if (a > 180) a = 180;
  float us = SERVO_MIN_US + (a / 180.0f) * (SERVO_MAX_US - SERVO_MIN_US);
  return (int)us;
}

// Conversión us -> ticks PCA9685
uint16_t usToTicks(int us) {
  float ticks = (SERVO_FREQ * 4096.0f * (float)us) / 1000000.0f;
  if (ticks < 0) ticks = 0;
  if (ticks > 4095) ticks = 4095;
  return (uint16_t)ticks;
}

// Set de un canal con ángulo absoluto (0..180), más offset e inversión
void setServoAngle(uint8_t ch, float angleDeg) {
  // Inversión por hardware lógico
  float a = angleDeg;
  if (servoDir[ch] < 0) a = 180.0f - a;
  int baseUs = angleToUs(a);
  int us = baseUs + servoOffsetUs[ch];
  uint16_t t = usToTicks(us);
  pca.setPWM(ch, 0, t);
}

// IK de una pata: retorna ángulos en grados (coxa, femur, tibia)
bool ikSolve(const Vec3 &target, float &aCoxa, float &aFemur, float &aTibia, bool isRightSide) {
  // Ajuste horizontal: coxa rota en planta por atan2(y, x)
  float a = atan2f(target.y, target.x); // rad
  aCoxa = a * 180.0f / M_PI; // grados

  // Proyección al plano de fémur-tibia: dist desde el eje de coxa
  float r = sqrtf(target.x*target.x + target.y*target.y) - L_COXA;
  float z = target.z;

  // Distancia al pie en el plano (r,z)
  float d = sqrtf(r*r + z*z);

  // Ley del coseno para aFemur y aTibia
  float cosTibia = (L_FEMUR*L_FEMUR + L_TIBIA*L_TIBIA - d*d) / (2.0f*L_FEMUR*L_TIBIA);
  if (cosTibia < -1.0f || cosTibia > 1.0f) return false;
  float tibiaRad = acosf(cosTibia); // 0..pi

  float cosFemur = (L_FEMUR*L_FEMUR + d*d - L_TIBIA*L_TIBIA) / (2.0f*L_FEMUR*d);
  if (cosFemur < -1.0f || cosFemur > 1.0f) return false;
  float femurRad = acosf(cosFemur);

  // Elevación natural: ángulo de la línea r-z
  float elev = atan2f(z, r);

  // Convenciones (ajusta según montaje mecánico):
  aFemur = (elev + femurRad) * 180.0f / M_PI - 10.0f;
  aTibia = (M_PI - tibiaRad) * 180.0f / M_PI - 10.0f;

  // Ajuste de simetría si es lado derecho
  if (isRightSide) {
    aCoxa = -aCoxa;
  }

  // Limitar a rangos seguros
  if (aCoxa < COXA_MIN) aCoxa = COXA_MIN;
  if (aCoxa > COXA_MAX) aCoxa = COXA_MAX;
  if (aFemur < FEMUR_MIN) aFemur = FEMUR_MIN;
  if (aFemur > FEMUR_MAX) aFemur = FEMUR_MAX;
  if (aTibia < TIBIA_MIN) aTibia = TIBIA_MIN;
  if (aTibia > TIBIA_MAX) aTibia = TIBIA_MAX;

  // Convertir a referencia 0..180 para servo:
  // Suponemos mid (90) como neutro mecánico aproximado.
  aCoxa = 90.0f + aCoxa;
  aFemur = 90.0f + aFemur;
  aTibia = 90.0f + aTibia;

  return true;
}

// ---------- Gait: trípode ----------
// Dos trípodes: {L0, R1, L2} y {R0, L1, R2}
uint8_t tripodA[3] = {0, 4, 2}; // índices de patas L0(0), R1(4), L2(2)
uint8_t tripodB[3] = {3, 1, 5}; // R0(3), L1(1), R2(5)

// Parámetros de movimiento:
float stepHeight = 25.0f;   // mm elevación
float stepLength = 40.0f;   // mm avance
float defaultX = 80.0f;     // mm delantero
float defaultY = 50.0f;     // mm lateral (separación)
float defaultZ = -60.0f;    // mm vertical (negativo hacia abajo)
uint16_t gaitPeriodMs = 550; // velocidad (ms por semiperiodo)

// Estado de control
enum Mode {MODE_STOP, MODE_FWD, MODE_BACK, MODE_LEFT, MODE_RIGHT, MODE_STEP};
Mode mode = MODE_STOP;

// Parser de comandos
String cmdBuffer;

// Sensor VL53L0X
Adafruit_VL53L0X lox;
uint16_t obstacleThresholdMm = 200; // parar si < 200 mm
bool obstacleDetected = false;

// Temporización
uint32_t lastGaitTick = 0;

// Posiciones base de cada pata en marco del cuerpo
Vec3 basePos[6];

void initBasePos() {
  // Asumir simetría: Y positivo lado izquierdo, negativo derecho
  basePos[0] = { defaultX,  defaultY, defaultZ}; // L0
  basePos[1] = { 0.0f,      defaultY, defaultZ}; // L1
  basePos[2] = {-defaultX,  defaultY, defaultZ}; // L2
  basePos[3] = { defaultX, -defaultY, defaultZ}; // R0
  basePos[4] = { 0.0f,     -defaultY, defaultZ}; // R1
  basePos[5] = {-defaultX, -defaultY, defaultZ}; // R2
}

void applyLegAngles(uint8_t legIdx, float aCoxa, float aFemur, float aTibia) {
  const LegMap &lm = legs[legIdx];
  setServoAngle(lm.coxa, aCoxa);
  setServoAngle(lm.femur, aFemur);
  setServoAngle(lm.tibia, aTibia);
}

void moveLegTo(uint8_t legIdx, const Vec3 &p) {
  float aC,aF,aT;
  bool rightSide = (legIdx >= 3);
  if (ikSolve(p, aC, aF, aT, rightSide)) {
    applyLegAngles(legIdx, aC, aF, aT);
  }
}

// Genera objetivo por pata según fase del trípode
void computeTargets(float phase, Vec3 outTargets[6]) {
  // phase: 0..1 (semiperiodo) alterna trípodes A/B
  // movimiento según modo:
  float dx = 0, dy = 0;
  if (mode == MODE_FWD) dx = stepLength;
  else if (mode == MODE_BACK) dx = -stepLength;
  else if (mode == MODE_LEFT) dy = stepLength;
  else if (mode == MODE_RIGHT) dy = -stepLength;

  // Para cada pata, si pertenece al grupo activo en esta mitad, elevar y avanzar, si no, retroceder a ras de suelo
  auto inTripod = [&](uint8_t leg, const uint8_t group[3]) {
    return (leg == group[0] || leg == group[1] || leg == group[2]);
  };

  const uint8_t* activeGroup = ((millis() / gaitPeriodMs) % 2 == 0) ? tripodA : tripodB;

  for (uint8_t i=0; i<6; ++i) {
    Vec3 base = basePos[i];
    Vec3 p = base;
    float t = phase; // 0..1 normalizado

    if (mode == MODE_STOP) {
      // Mantener base
      // Si hay STEP, se maneja externamente
    } else {
      if (inTripod(i, activeGroup)) {
        // Fase de swing (elevar y mover hacia adelante)
        float lift = stepHeight * sinf(t * M_PI); // campana
        p.z = base.z + lift;
        p.x = base.x + dx * (t - 0.5f); // centrado
        p.y = base.y + dy * (t - 0.5f);
      } else {
        // Fase de stance (contacto, mover hacia atrás de forma complementaria)
        p.z = base.z; // suelo
        p.x = base.x - dx * (t - 0.5f);
        p.y = base.y - dy * (t - 0.5f);
      }
    }

    outTargets[i] = p;
  }
}

void allLegsToHome() {
  for (uint8_t i=0; i<6; ++i) {
    moveLegTo(i, basePos[i]);
  }
}

// ---------- Comunicación por Zigbee (Serial1, transparente) ----------
void handleSerial1() {
  while (Serial1.available()) {
    char c = (char)Serial1.read();
    if (c == '\r') continue;
    if (c == '\n') {
      processCommand(cmdBuffer);
      cmdBuffer = "";
    } else {
      if (cmdBuffer.length() < 64)
        cmdBuffer += c;
    }
  }
}

void sendStatus(const String &s) {
  Serial1.print("[HEX] ");
  Serial1.println(s);
  Serial.print("[HEX] ");
  Serial.println(s);
}

void processCommand(const String &cmd) {
  String up = cmd;
  up.trim();
  up.toUpperCase();

  if (up == "FWD") { mode = MODE_FWD; sendStatus("MODE=FWD"); }
  else if (up == "BACK") { mode = MODE_BACK; sendStatus("MODE=BACK"); }
  else if (up == "LEFT") { mode = MODE_LEFT; sendStatus("MODE=LEFT"); }
  else if (up == "RIGHT") { mode = MODE_RIGHT; sendStatus("MODE=RIGHT"); }
  else if (up == "STOP") { mode = MODE_STOP; sendStatus("MODE=STOP"); allLegsToHome(); }
  else if (up.startsWith("SPEED ")) {
    int v = up.substring(6).toInt();
    if (v >= 300 && v <= 1200) {
      gaitPeriodMs = (uint16_t)v;
      sendStatus("SPEED(ms)=" + String(gaitPeriodMs));
    } else {
      sendStatus("ERR SPEED [300..1200]");
    }
  } else if (up.startsWith("STEP")) {
    mode = MODE_STEP;
    sendStatus("MODE=STEP (single)");
  } else if (up.startsWith("CALIB ")) {
    // Formato: CALIB leg dof offset_us
    // leg=0..5, dof=0(coxa)/1(femur)/2(tibia)
    int leg=-1, dof=-1, off=0;
    int n = sscanf(up.c_str(), "CALIB %d %d %d", &leg, &dof, &off);
    if (n==3 && leg>=0 && leg<6 && dof>=0 && dof<3 && off>-500 && off<500) {
      uint8_t ch = (dof==0) ? legs[leg].coxa : (dof==1 ? legs[leg].femur : legs[leg].tibia);
      servoOffsetUs[ch] = off;
      sendStatus("CALIB OK leg="+String(leg)+" dof="+String(dof)+" off="+String(off));
      // Reaplica home con nuevo offset
      moveLegTo(leg, basePos[leg]);
    } else {
      sendStatus("ERR CALIB usage: CALIB leg(0..5) dof(0..2) offset(-499..499)");
    }
  } else {
    sendStatus("UNKNOWN CMD: " + up);
  }
}

// ---------- VL53L0X ----------
bool readObstacle(uint16_t &mm) {
  VL53L0X_RangingMeasurementData_t measure;
  lox.rangingTest(&measure, false); // no debug
  if (measure.RangeStatus == 4) { // out of range
    return false;
  } else {
    mm = measure.RangeMilliMeter;
    return true;
  }
}

// ---------- Setup ----------
void setup() {
  Serial.begin(115200);
  Serial1.begin(115200); // XBee
  delay(50);

  Wire.begin();
  Wire.setClock(400000); // I2C rápido
  pca.begin();
  pca.setPWMFreq(SERVO_FREQ);
  delay(10);

  if (!lox.begin()) {
    Serial.println("VL53L0X no detectado. Verifique conexiones.");
  } else {
    Serial.println("VL53L0X listo.");
  }

  initBasePos();
  allLegsToHome();

  Serial.println("Hexapod listo. Comandos: FWD/BACK/LEFT/RIGHT/STOP/SPEED n/STEP/CALIB leg dof off");
  sendStatus("READY");
}

// ---------- Loop ----------
void loop() {
  handleSerial1();

  // Sensado de obstáculo
  uint16_t dist;
  if (readObstacle(dist)) {
    if (dist < obstacleThresholdMm) {
      if (!obstacleDetected) {
        obstacleDetected = true;
        mode = MODE_STOP;
        sendStatus("OBSTACLE " + String(dist) + "mm -> STOP");
        allLegsToHome();
      }
    } else {
      if (obstacleDetected) {
        obstacleDetected = false;
        sendStatus("PATH CLEAR");
      }
    }
  }

  // Gait update
  uint32_t now = millis();
  if (now - lastGaitTick >= 20) { // 50 Hz update
    lastGaitTick = now;

    // Calcular fase del semiperiodo
    uint32_t t = now % gaitPeriodMs;
    float phase = (float)t / (float)gaitPeriodMs; // 0..1

    Vec3 targets[6];
    computeTargets(phase, targets);

    if (mode == MODE_STEP) {
      // Ejecuta una mitad de ciclo y luego STOP
      static bool stepStarted = false;
      static uint32_t stepStartTime = 0;
      if (!stepStarted) {
        stepStarted = true;
        stepStartTime = now;
      }
      for (uint8_t i=0; i<6; ++i) moveLegTo(i, targets[i]);
      if (now - stepStartTime >= gaitPeriodMs) {
        mode = MODE_STOP; stepStarted = false;
        allLegsToHome();
        sendStatus("STEP DONE");
      }
    } else if (mode == MODE_STOP) {
      // Mantener home
      // no-op para evitar jitter
    } else {
      for (uint8_t i=0; i<6; ++i) moveLegTo(i, targets[i]);
    }
  }
}

Breve explicación de las partes clave:
– Configuración del PCA9685 a 50 Hz (SERVO_FREQ = 50) y conversión de microsegundos a ticks (usToTicks).
– Estructura LegMap para asociar canales a cada DOF de cada pata.
– IK simplificada: separa rotación de coxa (atan2 en planta) y resuelve fémur/tibia con ley del coseno en el plano r-z.
– Gait trípode: alterna grupos A y B; una mitad eleva y avanza, la otra mitad mantiene contacto y “arrastra” en sentido contrario para el ciclo de paso.
– Parser de comandos (Serial1) para XBee en modo transparente a 115200 bps.
– VL53L0X: al detectar un obstáculo por debajo de 200 mm, detiene el movimiento y centra.
– Calibración en caliente por offset por-servo (microsegundos) con comando CALIB.

Compilación/flash/ejecución

Asegúrate de tener conectado el Arduino Mega 2560 por USB. Identifica el puerto (Linux suele ser /dev/ttyACM0 o /dev/ttyUSB0).

1) Instalar Arduino CLI 0.35.3 (Linux):

# Descarga e instalación
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=$HOME/.local/bin sh -s 0.35.3

# Verificar versión
$HOME/.local/bin/arduino-cli version
# arduino-cli Version: 0.35.3

# Añadir al PATH (opcional, si no lo tienes):
echo 'export PATH=$HOME/.local/bin:$PATH' >> ~/.bashrc
source ~/.bashrc

2) Configurar core y bibliotecas exactas:

arduino-cli core update-index
arduino-cli core install arduino:avr@1.8.6

arduino-cli lib install "Adafruit PWM Servo Driver Library@2.4.1"
arduino-cli lib install "Adafruit BusIO@1.14.5"
arduino-cli lib install "Adafruit Unified Sensor@1.1.14"
arduino-cli lib install "Adafruit VL53L0X@1.3.1"

3) Compilar (FQBN para Mega 2560: arduino:avr:mega):

# Posicionarse en el directorio que contiene la carpeta servo_hexapod_zigbee/
arduino-cli compile --fqbn arduino:avr:mega servo_hexapod_zigbee

4) Subir al Mega 2560:

# Sustituye /dev/ttyACM0 por el puerto correcto de tu sistema
arduino-cli upload -p /dev/ttyACM0 --fqbn arduino:avr:mega servo_hexapod_zigbee

5) Monitor serie (USB) para logs de depuración:

arduino-cli monitor -p /dev/ttyACM0 -c baudrate=115200

6) Puente Zigbee (lado PC) con minicom (para enviar comandos al robot):

# Detecta el puerto del adaptador XBee USB, por ejemplo /dev/ttyUSB0
sudo apt-get install -y minicom
minicom -b 115200 -D /dev/ttyUSB0
# Escribe comandos: FWD, BACK, LEFT, RIGHT, STOP, SPEED 600, STEP, CALIB 0 1 20, etc.

Opcional (Python 3.10.12) para transmitir comandos al XBee remoto:

# archivo: send_zigbee.py
import sys, time, serial

port = "/dev/ttyUSB0"  # Cambia según tu sistema
baud = 115200
cmd = "FWD"            # o cualquier comando

if len(sys.argv) > 1:
    cmd = " ".join(sys.argv[1:])

with serial.Serial(port, baud, timeout=1) as ser:
    ser.write((cmd + "\n").encode("ascii"))
    time.sleep(0.1)
    # Leer respuesta del robot (eco por Zigbee)
    while ser.in_waiting:
        print(ser.readline().decode(errors="ignore").rstrip())

Ejecuta:

python3 send_zigbee.py "SPEED 600"
python3 send_zigbee.py "FWD"

Validación paso a paso

1) Verificación de I2C:
– Al abrir el monitor serie (USB), el programa debe imprimir “VL53L0X listo.” si el sensor es detectado. Si no, revisa SDA/SCL y VCC/GND.
– Los servos deberían llevar cada pata a su postura base (home) sin vibraciones notables.

2) Verificación de PCA9685 y servos:
– Debes observar un movimiento suave a posiciones centradas al iniciar.
– Si alguna articulación se mueve en sentido incorrecto, ajusta servoDir[] en el código y vuelve a subir.
– Ajusta offsets con CALIB para centrar mecánicamente:
– Ejemplo: “CALIB 0 1 20” corrige +20 us el fémur de L0.

3) Verificación del XBee (modo transparente):
– Desde minicom en el XBee remoto, envía “STOP”. Debes ver un eco “[HEX] MODE=STOP” tanto en minicom como en el monitor USB del Arduino.
– Envía “SPEED 700” y luego “FWD”. El robot debe iniciar un paso de trípode hacia adelante sin bloqueos.

4) Validación de locomoción:
– Con “FWD” el robot alterna trípodes. Observa que tres patas se elevan mientras las otras tres soportan.
– Cambia a “LEFT” o “RIGHT” y confirma el giro sobre el plano (ajuste lateral con dy).

5) Evitación con VL53L0X:
– Acerca un objeto al sensor frontal. Cuando esté a menos de ~200 mm, el robot debe emitir “[HEX] OBSTACLE xxxmm -> STOP” y volver a home.
– Al retirar el obstáculo, verás “[HEX] PATH CLEAR” y podrás reanudar con “FWD”.

6) Comando “STEP”:
– Ejecuta un semiperiodo de la marcha y vuelve a STOP automáticamente con “STEP DONE”.

7) Estabilidad eléctrica:
– Durante “FWD” sostenido, verifica que la fuente de servos no cae de tensión (ni reinicios del Mega).
– Toca el PCA9685: no debe estar excesivamente caliente. Si lo está, revisa la corriente de los servos y el duty.

8) Revisión de sincronía:
– Modifica “SPEED n” y evalúa la correspondencia entre n y la rapidez del paso. Valores muy bajos (<300 ms) pueden causar movimientos bruscos.

Troubleshooting

1) Servos tiemblan o se resetea el Mega al mover:
– Causa: falta de corriente o caída de tensión en V+ o masa no común.
– Solución: usa una fuente de 6–7.4 V con suficiente amperaje; une GND de fuente y GND del Mega; emplea cables gruesos y cortos.

2) VL53L0X no detectado (“no detectado” al iniciar):
– Causa: SDA/SCL invertidos, falta de VCC, mal módulo (3.3 V-only), nivel I2C incorrecto.
– Solución: en el Mega, SDA=20 y SCL=21; verifica VCC según módulo; prueba a 3.3 V si tu breakout no es 5V tolerant; revisa soldaduras.

3) Un grupo de servos se mueve al revés (pata gira al lado opuesto):
– Causa: inversión lógica no ajustada.
– Solución: cambia el signo en servoDir[ch] correspondiente (1 a -1). Recalibra con CALIB si es necesario.

4) No hay comunicación Zigbee (no respuestas en minicom):
– Causa: PAN ID distinto, baudios no coinciden, no están en misma red (coordinator/router).
– Solución: reconfigura ambos XBee con ATID igual, ATBD7 (115200), uno con ATCE1 (coordinator, lado PC) y el del robot con ATCE0 (router). Guarda con ATWR.

5) Compilación falla por bibliotecas:
– Causa: versiones no instaladas o dependencias faltantes.
– Solución: reinstala exactamente:
– arduino-cli lib install «Adafruit PWM Servo Driver Library@2.4.1»
– arduino-cli lib install «Adafruit BusIO@1.14.5»
– arduino-cli lib install «Adafruit Unified Sensor@1.1.14»
– arduino-cli lib install «Adafruit VL53L0X@1.3.1»

6) Servos no se mueven pero log por USB es correcto:
– Causa: PCA9685 sin V+ de potencia o sin GND común.
– Solución: aplica 6–7.4 V en V+ del PCA9685, conecta GND de la fuente a GND del PCA y del Mega.

7) Movimientos violentos al iniciar:
– Causa: offsets no calibrados o límites de ángulo mal configurados.
– Solución: ajusta servoOffsetUs[] y límites (COXA/FEMUR/TIBIA min/max). Empieza con allLegsToHome() antes de gait.

8) Lecturas erráticas de ToF:
– Causa: superficie brillante, ambiente IR saturado, tiempo de integración corto.
– Solución: promedia lecturas, sube el umbral o filtra por estados. Asegúrate de no tapar el sensor.

Mejoras/variantes

  • Migrar a API mode (AP=2) en XBee:
  • Permite direccionamiento a múltiples nodos, ACK y telemetría estructurada. Usa una librería XBee para frame parsing y añade CRC/timeout.

  • Calibración avanzada:

  • Guardar offsets y parámetros en EEPROM del Mega.
  • Añadir rutina de auto-calibración por guías impresas y un láser de referencia.

  • Gaits adicionales:

  • Ripple gait (estabilidad máxima), wave gait (lento y estable), amble (suavidad).
  • Transiciones suaves entre gaits según terreno.

  • Planificación local:

  • Usar el VL53L0X para mantener distancia objetivo, no solo stop. Integrar dos VL53L0X (frontal y lateral), cambiando dirección I2C de uno con pin XSHUT.

  • Telemetría:

  • Reporte periódico de estado (modo, distancia, velocidad, tensión batería).
  • Mando Zigbee con joystick o GUI en PC.

  • Gestión de energía:

  • Añadir sensor de corriente y voltaje (INA219) para limitar esfuerzos.
  • Modo reposo automático si no hay comando en N segundos.

  • Suavizado de trayectorias:

  • Interpolación spline/coseno para cada DOF, control feedforward de velocidad y aceleración.

  • Seguridad:

  • Watchdog (WDT) en el ATmega2560, kill-switch por comando, y botón físico de emergencia en línea V+.

Checklist de verificación

  • [ ] Arduino Mega 2560 detectado por el sistema (puerto serie visible).
  • [ ] Arduino CLI 0.35.3 instalado y en PATH.
  • [ ] Core arduino:avr@1.8.6 instalado sin errores.
  • [ ] Bibliotecas instaladas con versiones: Adafruit PWM Servo Driver 2.4.1, BusIO 1.14.5, Unified Sensor 1.1.14, VL53L0X 1.3.1.
  • [ ] PCA9685 conectado a SDA(20)/SCL(21), VCC=5 V, GND común; V+ con 6–7.4 V externa.
  • [ ] VL53L0X conectado al mismo bus I2C y detectado (mensaje “VL53L0X listo.”).
  • [ ] XBee S2C en el robot conectado a Serial1 (TX1=18, RX1=19) a 115200 bps vía shield/conversor nivel.
  • [ ] XBee remoto en PC configurado con el mismo PAN ID y baudios; se reciben ecos [HEX] en minicom al enviar comandos.
  • [ ] “STOP” recentra patas; “FWD/BACK/LEFT/RIGHT” mueven con trípode; “SPEED n” ajusta ritmo (300–1200 ms).
  • [ ] Acercar un objeto < 200 mm detiene el robot con mensaje de obstáculo.
  • [ ] Offsets calibrados por pata/DOF con “CALIB leg dof off” para posturas neutras.

Con esta práctica culminada, dispones de un servo-hexápodo controlado por Zigbee con un pipeline de toolchain reproducible (Arduino CLI), sensado ToF VL53L0X e integración estable de PCA9685 para 18 servos en un Arduino Mega 2560. El proyecto es una base sólida para evolucionar hacia control cinemático más avanzado, gaits adaptativos y redes Zigbee multipunto.

Encuentra este producto y/o libros sobre este tema en Amazon

Ir a Amazon

Como afiliado de Amazon, gano con las compras que cumplan los requisitos. Si compras a través de este enlace, ayudas a mantener este proyecto.

Quiz rápido

Pregunta 1: ¿Cuál es el sistema operativo recomendado para el proyecto?




Pregunta 2: ¿Qué versión de Arduino CLI se debe utilizar?




Pregunta 3: ¿Qué hardware se utiliza como driver de 16 canales servo?




Pregunta 4: ¿Cuál es la dirección por defecto del PCA9685?




Pregunta 5: ¿Qué tipo de sensor es el VL53L0X?




Pregunta 6: ¿Qué tipo de conversor se necesita para conectar el XBee S2C al Arduino Mega 2560?




Pregunta 7: ¿Qué biblioteca de Arduino se necesita para controlar el PCA9685?




Pregunta 8: ¿Qué módulo se utiliza para la comunicación Zigbee?




Pregunta 9: ¿Cuál es la opción de terminal serie recomendada para Linux?




Pregunta 10: ¿Cuántos servos se utilizan en el hexápodo del proyecto?




Carlos Núñez Zorrilla
Carlos Núñez Zorrilla
Electronics & Computer Engineer

Ingeniero Superior en Electrónica de Telecomunicaciones e Ingeniero en Informática (titulaciones oficiales en España).

Sígueme:
error: Contenido Protegido / Content is protected !!
Scroll to Top