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.
- 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
- 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
- SDA: GPIO 21
- SCL: GPIO 22
- Motor Pin 1: GPIO 32
- Motor Pin 2: GPIO 33
- Pulse Pin: GPIO 27
- Direction Pin: GPIO 26
- Enable Pin: GPIO 25
- LED Pin: GPIO 2
lib_deps =
https://github.com/micro-ROS/micro_ros_platformio
https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Librarytrajectory_msgs/msg/JointTrajectoryPoint- Arm joint controlstd_msgs/msg/Int32- Crane motor control
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
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;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};# Install PlatformIO CLI
pip install platformio
# Clone the repository
git clone https://github.com/screamlab/crane_esp32_rtos.git
cd crane_esp32_rtos- Open
include/params.hpp - Update WiFi credentials
- Set your Micro-ROS agent IP address
# Build the project
pio run
# Upload to ESP32
pio run --target upload
# Monitor serial output
pio device monitorYou can start the Micro-ROS agent using Docker or from source. For convenience, this project provides a startup script:
Use the provided script script/start_micro_ros_agent.sh to quickly launch the Micro-ROS agent in Docker.
- Make sure Docker is installed on your system.
- Set the ROS_DISTRO environment variable (e.g.
humble,galactic, etc.):export ROS_DISTRO=humble - Run the startup script:
bash script/start_micro_ros_agent.sh
#!/bin/bash
docker run -it --rm \
-p 8888:8888/udp \
microros/micro-ros-agent:$ROS_DISTRO \
udp4 --port 8888 -v4This 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
--portparameter in the script. - If you encounter permission issues, check
/devpermissions or run the script as root. - For serial or other transport options, refer to the official Micro-ROS agent documentation.
ζ¬ε°ζ‘ζδΎ script/run_crane_tui.sh εε Python ζεδ»ι’οΌTUIοΌι²θ‘εθ/ζ©ζ’°θζ§εΆγ
bash script/run_crane_tui.shζη΄ζ₯ε·θ‘ Python θ ³ζ¬οΌ
python3 script/crane_tui.pyζ€δ»ι’ε―η¨ζΌζ¬ε°η«―測試γ樑ζ¬ζθ micro-ROS agent δΊεγ
| Topic | Message Type | Description |
|---|---|---|
/joint_angles |
trajectory_msgs/JointTrajectoryPoint |
Robotic arm joint positions |
/crane_control |
std_msgs/Int32 |
Crane motor control commands |
# 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]
}"# 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 reverseThe system uses FreeRTOS with three main tasks:
-
Micro-ROS Task (Priority 5, 8KB stack)
- Manages ROS2 communication
- Handles agent connection/disconnection
- Processes incoming messages
-
Arm Control Task (Priority 2, 4KB stack)
- Controls 7-DOF robotic arm
- Smooth servo movement
- Angle constraint enforcement
-
Crane Control Task (Priority 2, 4KB stack)
- DC motor control (vertical movement)
- Stepper motor control (horizontal movement)
- Real-time motor state execution
WAITING_AGENT β AGENT_AVAILABLE β AGENT_CONNECTED
β β
βββββββββ AGENT_DISCONNECTED βββ
ArmManager armManager(NUM_OF_SERVOS, jointMinAngles, jointMaxAngles, jointInitAngles);
armManager.setServoTargetAngle(servo_index, angle);
armManager.moveArm();DC_motor_execute(state); // -1: down, 0: stop, 1: up
Stepper_motor_execute(state); // -1: backward, 0: stop, 1: forward- Task startup confirmations
- Micro-ROS connection status
- Error messages and diagnostics
- ON: Connected to Micro-ROS agent
- OFF: Disconnected or waiting for agent
# Monitor serial output
pio device monitor --baud 115200
# Check ROS2 topics
ros2 topic list
ros2 topic echo /joint_angles
ros2 topic echo /crane_control-
WiFi Connection Failed
- Verify SSID and password in
params.hpp - Check network accessibility
- Verify SSID and password in
-
Micro-ROS Agent Not Found
- Ensure agent is running on correct IP/port
- Check firewall settings
- Verify network connectivity
-
Servo Not Moving
- Check I2C connections (SDA=21, SCL=22)
- Verify servo power supply
- Check servo angle limits
-
Motor Control Issues
- Verify GPIO pin connections
- Check motor driver power
- Ensure proper grounding
# Clean build
pio run --target clean
# Verbose build output
pio run -v- Servo Update Rate: 100 Hz
- Motor Control Rate: 100 Hz
- ROS2 Communication: 5 Hz (ping) / Real-time (messages)
- Memory Usage: ~12KB RAM for tasks
- Fork the repository
- Create a feature branch (
git checkout -b feature/amazing-feature) - Commit your changes (
git commit -m 'Add amazing feature') - Push to the branch (
git push origin feature/amazing-feature) - Open a Pull Request
This project is licensed under the MIT License - see the LICENSE file for details.
- Micro-ROS for embedded ROS2 implementation
- Adafruit for PWM servo driver library
- PlatformIO for development environment
For questions and support:
- Open an issue on GitHub
- Check the Micro-ROS documentation
- Refer to ESP32 Arduino documentation
Made with β€οΈ by ScreamLab