![]() |
![]() |
This repository contains the driver stack for the four wheel differential drive base of the weeding robot shown above. It is a focused slice of a larger project titled Control and Navigation of a Weeding Robot. The complete system includes perception using IMU and LiDAR, a delta arm for mechanical removal, and higher level control such as sweep coverage, SLAM, and autonomous navigation.
Closed loop wheel velocity control using per wheel PID on ESP32 LEDC PWM.
Encoder odometry fused into a standard ROS 2 nav_msgs/Odometry message.
ROS 2 integration via micro ROS using Wi Fi UDP transport to a host agent.
Safe command handling with a command timeout that brings wheels to a stop.
- Hardware: ESP32, four DC gearmotors with quadrature encoders, H bridge drivers
- Middleware: micro ROS on the ESP32, ROS 2 Humble on the host
- Transport: UDP between agent and node
- Topics: subscribes to
/cmd_vel (geometry_msgs/Twist), publishes/wheel_odom (nav_msgs/Odometry)
The drive ESP32 acts as a micro ROS client. The ROS 2 agent runs on a laptop or small computer on the same network and bridges DDS traffic.
src/
├── main.cpp # tiny entry point
├── wheel_controller.cpp # PID per wheel, LEDC, H bridge drive
├── robot_drive.cpp # left right kinematics, encoder wiring, updates
├── odometry.cpp # tick integration and Odometry message fill
└── weedbot_node.cpp # Wi Fi, time sync, pub sub, executor
include/
├── config.h # pins, geometry, Wi Fi and agent settings
├── wheel_controller.h
├── robot_drive.h
├── odometry.h
└── weedbot_node.h
- Edit configuration
Update include/config.h with your Wi Fi SSID and password, and your agent IP and port. Wheel radius, wheel base, and ticks per revolution are also defined here.
- Build and flash
Use PlatformIO and the esp32dev environment. Connect your ESP32 to pins specified in config, then run build and upload from your IDE or use the CLI.
- Start the ROS 2 agent
On the host machine on the same network, run:
ros2 run micro_ros_agent micro_ros_agent udp4 --port 8888
- Send a command and watch odometry
# Set a gentle forward motion
ros2 topic pub /cmd_vel geometry_msgs/Twist '{linear: {x: 0.2}, angular: {z: 0.0}}' -r 5
# Echo wheel odometry
ros2 topic echo /wheel_odom
WHEEL_RADIUSin metersWHEEL_BASEin metersTICKS_PER_REV_FRONTper wheel revolution- PID gains in WheelController: Kp, Ki, Kd
CMD_TIMEOUT_MSsafety stop window
Tune these values to your robot's specifications.
The node blocks until time sync succeeds with the agent. This ensures consistent timestamps in wheel_odom for SLAM and higher level navigation tasks. If Wi Fi drops, the node attempts to reconnect and re sync before publishing again.
- Perception on a second ESP32: LiDAR scans and IMU yaw and yaw rate
- Removal on a third ESP32: delta arm kinematics, drill motor, dig sequence
- Higher level control: sweep coverage, SLAM toolbox mapping, navigation
The driver stack is part of a dissertation project titled Control and Navigation of a Weeding Robot.


