Skip to content

engarafa55/Ros2-Arduino-Bridge

Repository files navigation

πŸ€– ROS Arduino Bridge Firmware

Status Platform Architecture Layer Language License


πŸ“‘ Table of Contents


πŸ“– Project Overview

The ROS Arduino Bridge is a high-performance Firmware-Level Low-Level Controller designed to interface a ROS 2 (Robot Operating System) Navigation Stack with differential drive mobile robots. It acts as the critical hardware abstraction layer, converting high-level velocity commands (cmd_vel) into precise motor PWM signals while providing real-time odometry feedback.

❓ Problem Statement

A high-level PC running ROS cannot directly control hardware motors or read raw encoder pulses with the necessary real-time precision (sub-millisecond latency). Standard USB-Serial interfaces introduce jitter, and direct GPIO control from a PC is not feasible.

πŸ’‘ Solution & Utility

This firmware solves these challenges by:

  1. Real-Time PID Loop: Running a dedicated 30Hz Control Loop on the microcontroller to maintain target velocities.
  2. Hardware Abstraction: Encapsulating the complexities of different motor drivers (L298, MDD10A) and encoder types behind a unified Serial API.
  3. Auxiliary Control: integrating support for secondary mechanisms like a Stepper Motor Lift.

πŸ— System Architecture

The system follows a Server-Client Architecture where the Arduino acts as a dumb execution node controlled by the ROS PC.

🧩 Block Diagram

graph TD
    subgraph Host ["ROS 2 Host (PC/SBC)"]
        Nav["Navigation Stack"]
        Driver["Python Serial Driver"]
    end

    subgraph MCU ["Firmware (Arduino)"]
        Serial["Serial Command Parser"]
        PID["PID Controller (30Hz)"]
        Drivers["Motor & Encoder Drivers"]
        StepperCtrl["Lift Controller"]
    end

    subgraph Hardware ["Robot Hardware"]
        Motors["DC Motors (L/R)"]
        Encoders["Quadrature Encoders"]
        Lift["Stepper Mechanism"]
    end

    %% Navigation and Base Control
    Nav -->|"cmd_vel (Twist)"| Driver
    Driver -->|"m 20 20 (Target Ticks)"| Serial
    Serial -->|"Set Setpoint"| PID
    PID -->|"PWM"| Drivers
    Drivers -->|"Power"| Motors
    Encoders --"Pulse A/B"--> Drivers
    Drivers --"ISR Count"--> PID
    PID --"e (Encoder Ticks)"--> Serial

    %% Lift System Integration
    Driver -->|"s 100 (Lift Pos)"| Serial
    Serial -->|"Steps/Dir"| StepperCtrl
    StepperCtrl -->|"Pulse"| Lift

    %% Feedback Loop
    Serial --"Odometry"--> Driver
Loading

🧬 Component Roles

  1. Main Loop (Scheduler): Handles Serial polling and task dispatching.
  2. PID Controller: Calculates the motor output ($Output = K_p e(t) + K_i \int e(t) dt + K_d \frac{de(t)}{dt}$) to match target speeds.
  3. Command Parser: Interprets ASCII commands for Motor control (m), Encoders (e), and Lift (l).
  4. Hardware Drivers:
    • Motor Driver: H-Bridge control logic.
    • Encoder Driver: Interrupt-based pulse counting.
    • Stepper Driver: Non-blocking lift control.

🧠 Deep Technical Logic

πŸ”„ System Workflow

The system operates as a Non-Blocking Super-Loop with Interrupt support:

1. Setup Phase

  • Initialization: Configures Serial at 57600 baud.
  • Hardware Init: Sets Pin Modes for PWM, Direction, and Interrupts.
  • State Reset: Zeros out all PID integrators and encoder counters.

2. Communication Phase (Serial Polling)

  • The system listens for ASCII commands ending in \r.
  • Protocol:
    • m <L> <R>: Set PID target velocities (Ticks/Frame).
    • e: Read accumulated encoder counts.
    • o <L> <R>: Raw PWM override (Open Loop).
    • p <Kp>:<Kd>:<Ki>:<Ko>: Update PID constants.
    • l <1/0>: Move Lift Up/Down.
  • Priority Switch: If l (Lift) command is active, the PID loop is suspended to prioritize Stepper pulse generation.

3. Control Phase (PID Loop)

  • Executed strictly at 30 Hz (every ~33ms).
  • Input: Delta Encoder Ticks (Current - Prev).
  • Algorithm: Discrete PID with basic Anti-Windup.
  • Output: PWM (0-255) sent to Motor Driver.

⏳ Control Flow & Timing Analysis

1. PID Timing

  • Frequency: 30 Hz.
  • Implementation: if (millis() > nextPID) { updatePID(); }.
  • Jitter: Dependent on loop() execution time. Heavy Serial traffic or blocking Stepper calls can induce jitter.

2. Encoder Interrupts

  • Mechanism: Pin Change Interrupts (PCINT) using direct Port Register access (PIND, PINC).
  • Latency: Sub-microsecond execution time.
  • Precision: 1x, 2x, or 4x decoding supported via Lookup Table.

3. Critical Safety & Power Interlocks

  • Lift-Drive Power Interlock (Stop-to-Lift):
    • Behavior: The PID loop and main drive motors are intentionally blocked (setMotorSpeeds(0,0)) while runStepper() is active.
    • Design Rationale:
      1. Mechanical Stability (Center of Gravity): Operating the lift shifts the robot's vertical Center of Gravity (CoG). Inhibiting base movement prevents tipping hazards caused by dynamic acceleration forces during the lifting process.
      2. Power Management (Current Budgeting): The Stepper Motor is a high-current inductive load. Activating it simultaneously with the DC Drive Motors could exceed the battery's maximum discharge rate or the voltage regulator's limits, leading to brownouts. This Software Power Interlock ensures that high-current systems never operate in parallel.
  • Safety Timeout: An AUTO_STOP_INTERVAL checks for lost communication. If no valid m or o command is received, motors are disabled.

πŸ›‘ Performance & Safety Considerations

  • Failsafe Timeout: Currently set to 200,000 ms (200 seconds).

    [!WARNING] Safety Critical: The default AUTO_STOP_INTERVAL is set to 200s, which is dangerous for real-world operation. It is strongly recommended to reduce this to 2000 ms (2s) or less to ensure the robot stops immediately if connection is lost.

  • Atomic Access & Race Conditions:
    • Encoder variables (volatile long) are 32-bit integers. On an 8-bit AVR (Arduino Uno/Mega), reading these is not atomic (requires 4 byte fetches).
    • Risk: An ISR could fire between byte reads, corrupting the value.
    • Solution: It is critical to use ATOMIC_BLOCK(ATOMIC_RESTORESTATE) when reading encoder values in the main loop to ensure data integrity.
  • PWM Saturation: Outputs are clamped to MAX_PWM (255) to protect H-Bridges.
  • Derivative Kick: The PID derivative term is calculated on Measurement (Input), not Error, to prevent violent spikes when setpoints are changed instantaneously.

πŸ”Œ Hardware Mapping

Module Pin Name Arduino Pin Function
Left Motor PWM / Dir D6 / D7 MDD10A Drive / Direction
Right Motor PWM / Dir D5 / D4 MDD10A Drive / Direction
Left Enc A / B D2 / D3 Interrupt (Int0/Int1 or PCINT)
Right Enc A / B A1 / A0 Interrupt (PCINT on Analog)
Stepper Step / Dir / En D10 / D9 / D11 Lift Mechanism Control
Comms TX / RX D1 / D0 UART Serial (57600)

πŸ“‚ Folder Structure

/RosArduinoBridge
β”œβ”€β”€ RosArduinoBridge.ino  # Main Entry Point & Setup/Loop
β”œβ”€β”€ commands.h            # Serial Protocol Definitions
β”œβ”€β”€ diff_controller.h     # PID Algorithm Implementation
β”œβ”€β”€ motor_driver.h        # Motor Hardware Abstraction
β”œβ”€β”€ motor_driver.ino      # Motor Driver Implementations (L298/MDD10A)
β”œβ”€β”€ encoder_driver.h      # Encoder Hardware Abstraction
β”œβ”€β”€ encoder_driver.ino    # Encoder Interrupt Routines
β”œβ”€β”€ stepper.h             # Stepper Motor Definitions
└── stepper.ino           # Lift Control Logic

⚑ Simulation & Usage

Testing via Serial Monitor

  1. Connect: Plug Arduino into USB. Open Serial Monitor at 57600 baud.
  2. Line Endings: Set to Carriage Return or Both NL & CR.
  3. Commands:
    • Send e: Response 0 0 (assuming reset).
    • Send m 20 20: Motors should spin.
    • Send e again: Response should increase (e.g., 150 148).
    • Send l 1: Lift Stepper should activate.

πŸ›  Build & Deploy

Prerequisites

  • IDE: Arduino IDE 1.8+ or PlatformIO.
  • Libraries: AccelStepper (if using Stepper features).

Compilation

  1. Open RosArduinoBridge.ino.
  2. Select Board: Arduino Uno or Arduino Mega 2560.
  3. Config: check USE_BASE is defined. Check MDD10A_MOTOR_DRIVER or L298_MOTOR_DRIVER is selected.
  4. Flash: Upload to board.

βš™οΈ Motor Driver Configuration

The firmware includes built-in support for two different motor driver types to suit different robot builds:

  • L298 H-Bridge: Standard low-cost driver (uses Enable + IN1 + IN2).
  • Cytron MDD10A: High-power single-channel driver (uses PWM + Direction).

How to Switch: Driver selection is handled via compile-time macros.

RosArduinoBridge.ino:

/* Define your motor driver here: L298 or MDD10A */
#ifdef USE_BASE
   /* Encoders directly attached to Arduino board */
   #define ARDUINO_ENC_COUNTER

   /* Define your motor driver here: L298 or MDD10A */
   #define MDD10A_MOTOR_DRIVER // For MDD10A motor driver
   // #define L298_MOTOR_DRIVER // For L298 driver
#endif

Simply uncomment the line corresponding to your hardware and comment the other.


πŸ—‚ Driver Documentation

1. Motor Driver

Purpose: Abstracts H-Bridge logic.

  • Supported Chips: L298, MDD10A (Cytron).

  • Key API: setMotorSpeeds(int left, int right).

  • Logic: Handles sign conversion. Negative speed -> Set Direction Bit + PWM.


2. Encoder Driver

Purpose: Captures wheel rotation.

  • Mode: Interrupt-Driven (Robust against polling misses).

  • Key API: readEncoder(int i).

  • Implementation: Uses direct Port Manipulation (PIND & 0x0C) for maximum speed inside ISRs.


3. Diff Controller (PID)

Purpose: Closed-loop velocity control.

  • Tuning:

    • Kp = 20, Kd = 12, Ki = 0, Ko = 50.
  • Model: Velocity-based (Ticks per 33ms frame).

  • Features: Includes Integrated Windup guard and Differential Kick suppression.


4. Stepper Driver

Purpose: Control auxiliary lift mechanism.

  • Wrapper: Wraps functionality using AccelStepper library.
  • Key API: liftUp(), liftDown().
  • Blocking: Note that Stepper movement currently preempts wheel movement.

πŸ“ Source Files Overview

  • RosArduinoBridge.ino
    • Description: The main entry point that initializes the system, handles Serial polling, and schedules the 30Hz PID loop.
    • Role:
      void loop() {
        /* 1. Run Stepper logic (Priority #1) */
        #ifdef USE_BASE
          runStepper();
        #endif
      
        /* 2. Process Serial Commands */
        if (Serial.available() > 0) {
          // ... Parse ...
          runCommand();
        }
      
        /* 3. Run PID at 30Hz */
        if (millis() > nextPID) {
          updatePID();
          nextPID += PID_INTERVAL;
        }
      }

  • commands.h
    • Description: Defines the single-character ASCII protocol commands used to communicate with the ROS driver.
    • Role:
      #define READ_ENCODERS  'e'
      #define MOTOR_SPEEDS   'm'
      #define MOTOR_RAW_PWM  'o'
      #define RESET_ENCODERS 'r'
      #define UPDATE_PID     'p'
      #define LIFT_CONTROL   'l'

  • diff_controller.h
    • Description: Implements the PID algorithm for velocity control, including derivative kick prevention and integral windup guards.
    • Role:
      /* PID routine to compute the next motor commands */
      void doPID(SetPointInfo * p) {
         /* Proportional Error */
         Perror = p->TargetTicksPerFrame - (p->Encoder - p->PrevEnc);
      
         /* Derivative Error (on Measurement) */
         // output = (Kp * Perror - Kd * (input - p->PrevInput) + p->ITerm) / Ko;
         
         /* Integral term handling with anti-windup */
         p->ITerm += Ki * Perror;
      
         p->output = output;
      }

  • motor_driver.ino
    • Description: Handles the low-level hardware interaction for different motor drivers (L298, MDD10A), converting logical speeds to PWM signals.
    • Role:
      void setMotorSpeed(int i, int spd) {
        if (spd < 0) {
          spd = -spd;
          reverse = 1;
        }
        if (reverse == 0) digitalWrite(LEFT_MOTOR_DIRECTION, HIGH);
        analogWrite(LEFT_MOTOR_PWM, spd);
        }

  • encoder_driver.ino
    • Description: Uses Pin Change Interrupts (PCINT) to capture every encoder tick with sub-microsecond latency.
    • Role:
      /* Interrupt routine for LEFT encoder */
      ISR (PCINT2_vect){
        static uint8_t enc_last=0;
        enc_last <<=2; // Shift previous state
        enc_last |= (PIND & (3 << 2)) >> 2; // Read bits 2 and 3
        left_enc_pos += ENC_STATES[(enc_last & 0x0f)];
      }

  • stepper.ino
    • Description: Manages the auxiliary stepper motor for the lift mechanism, ensuring it reaches target positions safely.
    • Role:
      void liftUp() {
        if (!isLiftUp) {
          digitalWrite(STP_ENA_PIN, LOW); // Enable
          liftStepper.move(TARGET_POSITION);
          isLiftUp = true;
        }
      }

πŸš€ Future Improvements

  • Safety Fix: Reduce AUTO_STOP_INTERVAL to 2 seconds standard.
  • Non-Blocking Lift: Refactor runStepper() to allow simultaneous driving and lifting.
  • Binary Protocol: Switch from ASCII to a Packet-based (Binary) Serial protocol for lower overhead.
  • Atomic Macros: Wrap encoder reads in ATOMIC_BLOCK to prevent ISR race conditions.

πŸ‘¨πŸ’» Author

Abdelrahman Arafa

πŸ“§ Email: engarafa55@gmail.com

Building Intelligence, One Robot at a Time.


About

High-performance ROS 2 firmware for differential drive robots with Lift Mechanism support (Arduino). Features; a 30Hz real-time PID loop, interrupt-based odometry, and safety-critical interlocks for warehouse lift mechanisms.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

 
 
 

Contributors