API Reference Manual

Complete Command and API Documentation

1. GCode Commands

1.1 Motion Commands

Command Parameters Description Example
G0 X, Y, Z, F Rapid positioning (linear interpolation) G0 X10 Y20 Z-200
G1 X, Y, Z, F Linear interpolation with speed control G1 X50 F1000
G4 P Dwell (delay), P in milliseconds G4 P500 (wait 500ms)
G28 None Homing (return to reference position) G28
G90 None Absolute positioning mode G90
G91 None Relative positioning mode G91
G92 X, Y, Z Set current position as specified value G92 X0 Y0 Z0

1.2 M Commands (Auxiliary Functions)

Command Function Example
M3 Turn ON vacuum pump M3
M5 Turn OFF vacuum pump M5
M7 Turn ON solenoid valve (suction) M7
M9 Turn OFF solenoid valve (release) M9
M17 Enable motors (lock) M17
M18 Disable motors (unlock) M18
M114 Report current position M114X:10.0 Y:20.0 Z:-200.0

1.3 Parameter Units

  • X, Y, Z: millimeters (mm)
  • F: speed, mm/min (default 1000)
  • P: dwell time, milliseconds (ms)

2. Python API

2.1 Serial Communication Class

from serial import Serial
import time

class DeltaRobot:
    def __init__(self, port='COM3', baudrate=115200):
        """Initialize serial connection"""
        self.ser = Serial(port, baudrate, timeout=1)
        time.sleep(2)  # Wait for connection
        
    def send(self, gcode):
        """Send GCode command"""
        self.ser.write((gcode + '\n').encode())
        response = self.ser.readline().decode().strip()
        return response
        
    def home(self):
        """Homing"""
        return self.send("G28")
        
    def moveto(self, x, y, z, speed=1000):
        """Move to specified position"""
        cmd = f"G0 X{x} Y{y} Z{z} F{speed}"
        return self.send(cmd)
        
    def pick(self):
        """Suction (pump + valve ON)"""
        self.send("M3")
        self.send("M7")
        
    def release(self):
        """Release (valve OFF, pump OFF)"""
        self.send("M9")
        self.send("M5")
        
    def close(self):
        """Close serial port"""
        self.ser.close()

# Usage example
robot = DeltaRobot('COM3')
robot.home()
robot.moveto(10, 20, -200)
robot.close()

2.2 Vision Processing API

from ultralytics import YOLO
import cv2

class VisionDetector:
    def __init__(self, model_path='yolov8n.pt'):
        """Initialize YOLOv8 model"""
        self.model = YOLO(model_path)
        
    def detect(self, frame, conf=0.5):
        """
        Object detection
        
        Args:
            frame: Input image (numpy array)
            conf: Confidence threshold (0.0-1.0)
            
        Returns:
            detections: List[(x, y, w, h, class_id, confidence)]
        """
        results = self.model(frame, conf=conf)
        detections = []
        
        for r in results:
            boxes = r.boxes
            for box in boxes:
                x1, y1, x2, y2 = box.xyxy[0].tolist()
                w, h = x2 - x1, y2 - y1
                cx, cy = (x1 + x2) / 2, (y1 + y2) / 2
                cls = int(box.cls[0])
                conf = float(box.conf[0])
                
                detections.append((cx, cy, w, h, cls, conf))
                
        return detections

# Usage example
detector = VisionDetector()
cap = cv2.VideoCapture(0)

ret, frame = cap.read()
detections = detector.detect(frame)

for cx, cy, w, h, cls, conf in detections:
    print(f"Object at ({cx:.0f}, {cy:.0f}), class={cls}, conf={conf:.2f}")

3. Firmware API

3.1 Kinematics Functions

// File: esp32/robotGeometry.cpp

/**
 * Inverse kinematics: Calculate motor angles from end effector position
 * 
 * @param x0, y0, z0 End effector coordinates (mm)
 * @param theta1, theta2, theta3 Output motor angles (degrees)
 * @return 0:success, -1:out of range
 */
int delta_calcInverse(float x0, float y0, float z0,
                      float &theta1, float &theta2, float &theta3);

/**
 * Forward kinematics: Calculate end effector position from motor angles
 * 
 * @param theta1, theta2, theta3 Motor angles (degrees)
 * @param x0, y0, z0 Output end effector coordinates (mm)
 * @return 0:success, -1:solution not found
 */
int delta_calcForward(float theta1, float theta2, float theta3,
                      float &x0, float &y0, float &z0);

3.2 Interpolation Functions

// File: esp32/interpolation.cpp

class Interpolation {
public:
    // Set interpolation parameters
    void setInterpolation(
        float start_x, float start_y, float start_z,
        float end_x, float end_y, float end_z,
        float duration_ms
    );
    
    // Get current position (call in loop)
    void getInterpolation(float &x, float &y, float &z);
    
    // Check if interpolation complete
    bool isFinished();
};

4. Configuration Files

4.1 ESP32 Configuration (config.h)

// Serial communication
#define BAUD 115200

// Arm length parameters (mm)
#define LOW_SHANK_LENGTH 140.0    // Not used (see robotGeometry.cpp)
#define HIGH_SHANK_LENGTH 281.0   // Not used (see robotGeometry.cpp)
#define END_EFFECTOR_OFFSET 50.0  // End effector offset

// Motor parameters
#define MICROSTEPS 16             // Microstepping
#define STEPS_PER_REV 200         // Steps per revolution
#define MAIN_GEAR_TEETH 4.5       // Gear ratio

// Command queue
#define QUEUE_SIZE 10             // Max queued commands

// Interpolation mode
#define SPEED_PROFILE 2           // 0:constant, 1:trapezoidal, 2:cosine

// Workspace limits (mm)
#define Z_MIN -320.0              // Lowest Z
#define Z_MAX -140.0              // Highest Z

4.2 Actual Arm Lengths (robotGeometry.cpp)

⚠️ Important: Actual arm lengths are hard-coded in robotGeometry.cpp (lines 10-11), NOT in config.h.
// File: esp32/robotGeometry.cpp (line ~10)
float L = 150.0;  // Upper arm length (mm) - MODIFY THIS
float l = 281.0;  // Lower arm length (mm) - MODIFY THIS

4.3 Python Configuration (CameraDetect.py)

# Serial port settings
SERIAL_PORT = 'COM3'
BAUD_RATE = 115200

# Camera settings
CAMERA_ID = 0                    # Camera device ID
FRAME_WIDTH = 640               # Resolution width
FRAME_HEIGHT = 480              # Resolution height

# YOLO settings
MODEL_PATH = 'yolov8n.pt'       # Model file path
CONFIDENCE_THRESHOLD = 0.5      # Detection confidence threshold

# Coordinate transformation
HOMOGRAPHY_MATRIX = 'homography_matrix.npy'  # Transformation matrix file

Complete API Documentation

View source code comments for more detailed API documentation: