Skip to content

screamlab/crane_esp32_rtos

Folders and files

NameName
Last commit message
Last commit date

Latest commit

Β 

History

9 Commits
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 
Β 

Repository files navigation

ESP32 Crane Control System with Micro-ROS

A sophisticated robotic crane control system built on ESP32 using Micro-ROS for real-time communication. This project integrates a 7-DOF robotic arm with crane motor control capabilities, enabling precise manipulation and positioning tasks.

πŸš€ Features

  • Multi-DOF Robotic Arm Control: 7-servo robotic arm with precise angle control
  • Crane Motor System: Dual motor control (DC motor + Stepper motor)
  • Micro-ROS Integration: Real-time ROS2 communication over WiFi
  • FreeRTOS Multitasking: Concurrent task management for smooth operation
  • Hardware Abstraction: Clean separation between hardware control and business logic
  • Real-time Feedback: Live status monitoring and control

πŸ› οΈ Hardware Requirements

Core Components

  • ESP32 Development Board (ESP32-DOIT-DEVKIT-V1)
  • Adafruit PWM Servo Driver (PCA9685)
  • 7x Servo Motors (for robotic arm)
  • DC Motor (for crane vertical movement)
  • Stepper Motor (for crane horizontal movement)
  • Motor Driver Circuits

Pin Configuration

I2C Communication (Servo Control)

  • SDA: GPIO 21
  • SCL: GPIO 22

DC Motor Control

  • Motor Pin 1: GPIO 32
  • Motor Pin 2: GPIO 33

Stepper Motor Control

  • Pulse Pin: GPIO 27
  • Direction Pin: GPIO 26
  • Enable Pin: GPIO 25

Status Indicator

  • LED Pin: GPIO 2

πŸ“¦ Software Dependencies

PlatformIO Libraries

lib_deps =
    https://github.com/micro-ROS/micro_ros_platformio
    https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library

ROS2 Message Types

  • trajectory_msgs/msg/JointTrajectoryPoint - Arm joint control
  • std_msgs/msg/Int32 - Crane motor control

πŸ—οΈ Project Structure

crane_microRos/
β”œβ”€β”€ include/
β”‚   β”œβ”€β”€ armDriver.hpp          # Robotic arm control class
β”‚   └── params.hpp             # System configuration parameters
β”œβ”€β”€ src/
β”‚   β”œβ”€β”€ main.cpp              # Main application logic
β”‚   └── armDriver.cpp         # Arm control implementation
β”œβ”€β”€ lib/
β”œβ”€β”€ test/
└── platformio.ini            # Build configuration

βš™οΈ Configuration

Network Settings

Edit include/params.hpp to configure your network:

// WiFi Credentials
#define WIFI_SSID "your_wifi_ssid"
#define WIFI_PASSWORD "your_wifi_password"

// Micro-ROS Agent Configuration
const IPAddress AGENT_IP(192, 168, 1, 100);  // Replace with your agent IP
const uint16_t AGENT_PORT = 8888;

Hardware Parameters

Adjust servo limits and motor settings in params.hpp:

// Servo Configuration
const size_t NUM_OF_SERVOS = 7;
const uint8_t jointMinAngles[NUM_OF_SERVOS] = {0, 0, 0, 0, 0, 0, 0};
const uint8_t jointMaxAngles[NUM_OF_SERVOS] = {180, 180, 180, 180, 180, 180, 180};
const uint8_t jointInitAngles[NUM_OF_SERVOS] = {90, 90, 90, 90, 90, 90, 90};

πŸš€ Getting Started

1. Setup Development Environment

# Install PlatformIO CLI
pip install platformio

# Clone the repository
git clone https://github.com/screamlab/crane_esp32_rtos.git
cd crane_esp32_rtos

2. Configure Network Settings

  1. Open include/params.hpp
  2. Update WiFi credentials
  3. Set your Micro-ROS agent IP address

3. Build and Upload

# Build the project
pio run

# Upload to ESP32
pio run --target upload

# Monitor serial output
pio device monitor

4. Setup Micro-ROS Agent

You can start the Micro-ROS agent using Docker or from source. For convenience, this project provides a startup script:

5. Start Micro-ROS Agent with Script (Docker)

Use the provided script script/start_micro_ros_agent.sh to quickly launch the Micro-ROS agent in Docker.

Steps

  1. Make sure Docker is installed on your system.
  2. Set the ROS_DISTRO environment variable (e.g. humble, galactic, etc.):
    export ROS_DISTRO=humble
  3. Run the startup script:
    bash script/start_micro_ros_agent.sh

Script Content

#!/bin/bash
docker run -it --rm \
  -p 8888:8888/udp \
  microros/micro-ros-agent:$ROS_DISTRO \
  udp4 --port 8888 -v4

This will start the Micro-ROS agent and listen for UDP connections on port 8888.

Notes:

  • Make sure the ESP32 firmware is configured with the correct agent IP and port.
  • To change the port, edit the --port parameter in the script.
  • If you encounter permission issues, check /dev permissions or run the script as root.
  • For serial or other transport options, refer to the official Micro-ROS agent documentation.

6. Run Crane Control UI (crane_tui)

ζœ¬ε°ˆζ‘ˆζδΎ› script/run_crane_tui.sh ε•Ÿε‹• Python ζ–‡ε­—δ»‹ι’οΌˆTUIοΌ‰ι€²θ‘ŒεŠθ‡‚/ζ©Ÿζ’°θ‡‚ζŽ§εˆΆγ€‚

ε•Ÿε‹•ζ–ΉεΌ

bash script/run_crane_tui.sh

ζˆ–η›΄ζŽ₯執葌 Python θ…³ζœ¬οΌš

python3 script/crane_tui.py

ζ­€δ»‹ι’ε―η”¨ζ–Όζœ¬εœ°η«―ζΈ¬θ©¦γ€ζ¨‘ζ“¬ζˆ–θˆ‡ micro-ROS agent 互動。

πŸ“‘ ROS2 Interface

Subscribed Topics

Topic Message Type Description
/joint_angles trajectory_msgs/JointTrajectoryPoint Robotic arm joint positions
/crane_control std_msgs/Int32 Crane motor control commands

Control Commands

Robotic Arm Control

# Publish joint angles (in degrees)
ros2 topic pub /joint_angles trajectory_msgs/msg/JointTrajectoryPoint "{
  positions: [90.0, 45.0, 135.0, 90.0, 90.0, 90.0, 90.0]
}"

Crane Control

# Motor control states: -1 (reverse), 0 (stop), 1 (forward)
ros2 topic pub /crane_control std_msgs/msg/Int32 "data: 1"  # Move forward
ros2 topic pub /crane_control std_msgs/msg/Int32 "data: 0"  # Stop
ros2 topic pub /crane_control std_msgs/msg/Int32 "data: -1" # Move reverse

πŸ”§ System Architecture

Task Management

The system uses FreeRTOS with three main tasks:

  1. Micro-ROS Task (Priority 5, 8KB stack)

    • Manages ROS2 communication
    • Handles agent connection/disconnection
    • Processes incoming messages
  2. Arm Control Task (Priority 2, 4KB stack)

    • Controls 7-DOF robotic arm
    • Smooth servo movement
    • Angle constraint enforcement
  3. Crane Control Task (Priority 2, 4KB stack)

    • DC motor control (vertical movement)
    • Stepper motor control (horizontal movement)
    • Real-time motor state execution

State Machine

WAITING_AGENT β†’ AGENT_AVAILABLE β†’ AGENT_CONNECTED
      ↑                              ↓
      ←──────── AGENT_DISCONNECTED ←──

πŸŽ›οΈ Hardware Control API

Robotic Arm

ArmManager armManager(NUM_OF_SERVOS, jointMinAngles, jointMaxAngles, jointInitAngles);
armManager.setServoTargetAngle(servo_index, angle);
armManager.moveArm();

Motor Control

DC_motor_execute(state);     // -1: down, 0: stop, 1: up
Stepper_motor_execute(state); // -1: backward, 0: stop, 1: forward

πŸ” Monitoring and Debugging

Serial Monitor Output

  • Task startup confirmations
  • Micro-ROS connection status
  • Error messages and diagnostics

Status LED

  • ON: Connected to Micro-ROS agent
  • OFF: Disconnected or waiting for agent

Debug Commands

# Monitor serial output
pio device monitor --baud 115200

# Check ROS2 topics
ros2 topic list
ros2 topic echo /joint_angles
ros2 topic echo /crane_control

πŸ› οΈ Troubleshooting

Common Issues

  1. WiFi Connection Failed

    • Verify SSID and password in params.hpp
    • Check network accessibility
  2. Micro-ROS Agent Not Found

    • Ensure agent is running on correct IP/port
    • Check firewall settings
    • Verify network connectivity
  3. Servo Not Moving

    • Check I2C connections (SDA=21, SCL=22)
    • Verify servo power supply
    • Check servo angle limits
  4. Motor Control Issues

    • Verify GPIO pin connections
    • Check motor driver power
    • Ensure proper grounding

Build Issues

# Clean build
pio run --target clean

# Verbose build output
pio run -v

πŸ“ˆ Performance Characteristics

  • Servo Update Rate: 100 Hz
  • Motor Control Rate: 100 Hz
  • ROS2 Communication: 5 Hz (ping) / Real-time (messages)
  • Memory Usage: ~12KB RAM for tasks

🀝 Contributing

  1. Fork the repository
  2. Create a feature branch (git checkout -b feature/amazing-feature)
  3. Commit your changes (git commit -m 'Add amazing feature')
  4. Push to the branch (git push origin feature/amazing-feature)
  5. Open a Pull Request

πŸ“„ License

This project is licensed under the MIT License - see the LICENSE file for details.

πŸ™ Acknowledgments

πŸ“ž Support

For questions and support:


Made with ❀️ by ScreamLab

About

No description, website, or topics provided.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published