Main project developed in collaboration with Manchester Robotics, as part of the undergraduate courses "Robotics Foundation" and "Intelligent Robotics Implementation."
The goal was to control the speed of a brushed DC motor attached to one of the wheels of the Puzzlebot — Manchester Robotics’ educational, differential-drive mobile robot.
Although velocity control for the Puzzlebot’s wheels will later use pre-built facilities provided by Manchester Robotics, it is essential to first understand the core control principles.
One approach is open-loop control, where voltage is applied in proportion to the desired speed. However, this method may not be robust enough, since it lacks self-correction.
For this reason, a closed-loop controller was used: a PID. By applying proportional, integral, and derivative terms, the system can reduce error over time. This ensures that the actual speed converges to the desired value.
ROS 2 was used as the middleware to modularize and standardize the robotics software. In other words, it enables the development of a more organized and maintainable system.
Initially, two prototype nodes were created to test ROS2 functionality. The first node generated a sinusoidal signal, and the second acted as a signal processor. It subscribed to the signal generated by the first node, modified it, and published the processed signal. Both signals were visualized using rqt_plot
.
To implement this:
1. A ROS2 package named signal_processing
was created.
2. Inside this package, the signal_generator
node was developed. It used math.sin()
and a time variable t
that incremented on each callback to compute a sinusoidal wave. The resulting signal was published on the /signal
topic.
3. Next, the signal_processor
node was implemented. It subscribed to the /signal
topic and applied modifications to the incoming signal: a phase shift (using a trigonometric identity), reduced amplitude, and an offset. The processed signal was then published to its own topic /proc_signal
.
4. A launch file was added to start both nodes and open rqt_plot
for signal visualization.
After building the package, the full system can be launched with:
ros2 launch signal_processing signal_processing.launch.py
The signal_generator
node later evolved into the setpoint
node for a simulated PID control system. The simulation included three main nodes:
- setpoint
: published speed references.
- controller
: subscribed to both the setpoint and simulated motor output, computed the error, applied the PID algorithm, and published the control signal.
- dc_motor
: simulated motor dynamics using a first-order model, received the control input, updated the speed, and published feedback.
The code was updated to load node parameters directly from the launch file and to allow real-time tuning using rqt_reconfigure
.
The reference node was extended to support both sinusoidal and square wave signals. The signal type can also be changed in real time through dynamic configuration.
A new launch file was created to start three sets of motor controllers. To improve robustness, node execution order was managed using services, following this sequence:
1. dc_motor
2. controller
3. setpoint
After building the package, the full system can be launched with:
ros2 launch motor_control motor_control.launch.py
This setup allowed experimentation with PID parameters and performance evaluation before working with real hardware.
In the hardware phase, the setpoint
node ran on a PC and is located in the motor_control_real
package. The motor
node was implemented on an ESP32 microcontroller using micro-ROS. This node handled the full control loop. Its code can be found in the micro_ROS
folder.
The ESP32 used interrupts to read signals from a quadrature encoder and calculate the motor’s angular velocity. The motor
node subscribed to the setpoint
topic to receive the target speed from the PC. It then computed the error between the reference and the measured velocity, applied the PID algorithm to calculate the control output, and converted this into a PWM signal sent to the H-bridge to drive the motor.
To support system monitoring, the motor
node also published key data through dedicated topics: the encoder count, measured angular velocity, error value, and the applied control signal.
Angular velocity is measured using a quadrature encoder mounted on the motor shaft. Hardware interrupts capture changes in the encoder channels. The velocity is computed by counting encoder pulses over a fixed time interval. With a resolution of 12 pulses per motor shaft revolution and a 35:1 gear reduction ratio, the pulses are converted into radians per second at the output shaft. The final value is multiplied by 2 to account for full quadrature decoding.
To improve signal quality, which can be affected by noise, a low-pass filter is applied. This filter reduces high-frequency components—where abrupt changes in the signal appear—without significantly affecting response time. By attenuating these high frequencies and preserving the lower ones, the filtered signal more accurately represents the actual output of the system.
The PID controller is implemented in discrete form. The result is a control output that we feed as a PWM signal into a motor driver. The driver then provides a voltage to the motor, influencing its angular velocity. We measure this new velocity, closing the loop. Depending on the sign of the control signal, the motor driver also adjusts the motor’s direction. The entire system operates in a closed-loop control cycle running at a constant frequency of 50 Hz.
The setpoint
node publishes reference signals using configurable parameters: timer period, amplitude, and frequency. It supports multiple waveform types—such as sine, square, or step—and can either hold a fixed waveform or cycle through several. All parameters can be updated dynamically at runtime.
Quality of Service (QoS) settings were configured to ensure appropriate communication. The setpoint
node used the RELIABLE
policy to guarantee that reference signals consistently reached the motor
node, as these signals are critical for controlling a real-world system and must not be lost. On the other hand, the motor
node used the BEST_EFFORT
policy for non-critical data, such as debugging messages, where occasional packet loss is acceptable. This choice also helps reduce communication latency.
In addition, a state machine was implemented to establish and maintain the connection with the micro-ROS agent. In case of disconnection, it attempts to reconnect and reinitialize ROS 2 entities.
To tune the PID, a manual approach was used, where gains were adjusted through trial and error until the system responded satisfactorily. This process was not just guesswork; it followed the following general methodology:
The process began with a pure P controller. The proportional gain scales the error, so increasing the P value makes the system reach the setpoint faster. However, if the P gain is too high, it can cause oscillations.
The integral term was then added to eliminate steady-state error, helping the system reach and maintain the desired reference over time.
Finally, the derivative term was introduced. D-action provides damping but is highly sensitive to noise. Rapid changes in the signal generate large derivative values, which can amplify measurement noise. Due to the presence of noise in the setup, the D term was applied conservatively.
The sampling time is set to 50 Hz. In theory, a higher sampling frequency allows the controller to respond more effectively, as it receives more frequent updates about the system’s behavior. However, using ROS introduces overhead that is not present in basic microcontroller setups.
In this case, the system is limited by the executor's spin time, which also processes incoming setpoint data from the teleoperator. As a result, the controller cannot operate at a frequency higher than the rate at which new setpoint values can be reliably received.
Choosing an appropriate PWM frequency can significantly improve the performance and control of brushed DC motors. When calculating the equivalent voltage delivered by PWM, it is often assumed that the motor responds as if connected to a constant voltage source. However, this is not the case.
The rotor of a brushed DC motor consists of coils of wire wound around a laminated magnetic core, which makes it behave as an inductor. Inductors are electromagnetic components that accumulate energy through a gradually increasing magnetic field generated by current passing through the coil. Depending on the coil size, it may take several milliseconds to accumulate enough energy to rotate the shaft.
Because of this inductive behavior, DC motors perform best when the applied voltage is relatively constant, giving the magnetic field time to build up. At higher PWM frequencies, the pulses switch too quickly for the coil to gather sufficient energy, which can prevent the motor from spinning effectively.
Lowering the PWM frequency allows the motor coils to draw more energy from each pulse. This helps the motor start spinning at lower equivalent voltages and improves torque at low speeds. The goal is to select a frequency that provides good torque across the desired speed range while minimizing the vibration that can occur at lower frequencies.
As a general rule, most small brushed DC motors perform well with PWM frequencies between 50 Hz and 100 Hz. The selection is always a trade-off: motors run more smoothly and efficiently at higher frequencies, but control electronics are often more effective and stable at lower ones. In fact, some low-end motors require a strong initial pulse—achievable with low-frequency PWM—to overcome internal friction.
For small hobby motors (typically under 1A), using lower frequencies around 100 Hz tends to provide effective speed control. Higher frequencies may prevent the motor from starting or cause it to spin too fast.
For this project, a PWM frequency of 100 Hz was selected.
As an acceptance criterion, the mean square error (MSE) was calculated to evaluate the overall effectiveness of the controller. For the sine wave input, the MSE remained consistently below 1 throughout the test. In the case of the ramp signal, which features less abrupt variation, the MSE stayed below 0.25 — both indicating low error levels.
Controller robustness can also be assessed by observing its response to different types of input signals and external disturbances:
Component | Description |
---|---|
L298N Motor Driver | Dual H-bridge driver for controlling DC motors |
MCR2 Brushed DC Motor with Encoder | 6V, 35:1 gear ratio, 176 RPM |
ESP32 Dev Module | Microcontroller with Wi-Fi and Bluetooth support |
Power Supply | 12V regulated supply |
A single 12V power source is used, connected to the 12V input of the L298N. The onboard voltage regulator is enabled using the jumper. The 5V input pin should not be connected to any external supply, as it already outputs 5V through the onboard regulator. This 5V pin is proposed as a power source to supply the encoder.
You will need the Arduino IDE and ROS2 Humble installed on your system. This project was developed and tested on Ubuntu Linux 22.04 (Jammy Jellyfish).
The supported board for micro-ROS bare-metal projects using the Arduino IDE is the ESP32 Dev Module, using the Arduino core version 2.0.17.
First, go to the micro-ROS v2.0.6-humble release page and download the library ZIP file.
Then, include the library in your Arduino project via Sketch → Include Library → Add .ZIP Library...
.
Finally, flash the micro_ROS.ino
file found in the micro_ros
folder of this repository to the ESP32 board.
To set up the micro-ROS agent, run the provided micro_ros_setup
script located in the root of this repository. This script installs all dependencies and builds the agent.
Once the setup is complete and your system has been rebooted or logged back in (to apply serial port permissions), you can start the micro-ROS agent using the following command:
ros2 run micro_ros_agent micro_ros_agent serial --dev /dev/ttyUSB0
After building the motor_control_real
package, launch the full system using the command below:
ros2 launch motor_control_real motor_control_real.launch.py
Note: Make sure docker-compose
is installed.
Open a terminal in the root of the cloned repository and run the following command:
docker-compose up --build
This will build a Docker image named puzzlebot_image
and create a container named puzzlebot_container
, ready to use.
To remove the container along with its associated Docker Compose environment:
docker-compose down
To start the container:
docker start puzzlebot_container
To access the container:
docker exec -it puzzlebot_container bash
To stop the container:
docker stop puzzlebot_container
To remove just the container (without Docker Compose):
docker rm puzzlebot_container
At this point, you should have completed the hardware connections of the Puzzlebot, flashed the hackerboard firmware, and configured the Jetson using the provided Jetson image and its hotspot network.
- Turn on the Puzzlebot’s power supply.
- Connect to the Puzzlebot's hackerboard Wi-Fi network (SSID and password are shown on the OLED screen).
- Open a web browser and navigate to the default hackerboard IP (commonly
192.168.1.1
). - On the configuration page:
- In Active Modules, leave only
screen
enabled and click Save. - (Optional) Modify SSID and password under Network Settings and click Save.
- Under Motor-Encoder Settings, select Wheel Velocities Control Mode and click Save. This is necessary for joystick teleoperation (later controllers will use other mode).
- In Active Modules, leave only
- Click Change Configuration and set
CommType
onROS parameters
to 2 (Serial) inconfig_live.json
. Upload the new configuration to the robot. - Switch to the Puzzlebot's Jetson Wi-Fi network.
- Connect to the Jetson via SSH:
ssh <username>@<jetson_ip>
- Launch the micro-ROS agent on the Jetson:
ros2 launch puzzlebot_ros micro_ros_agent.launch.py
- In another terminal, build the workspace of the cloned repository.
- Connect an Xbox One Elite Series controller (or any joystick). You may customize the joystick config files in:
puzzlebot_control/config/joystick_config.yaml
puzzlebot_control/config/joystick_teleop.yaml
- Run the joystick teleoperation launch file:
ros2 launch puzzlebot_bringup joystick_sim_real_teleop_bringup.launch.py
This will also launch a Gazebo simulation acting as a digital twin. It subscribes to the same velocity command topic as the real Puzzlebot, allowing both to move in approximate synchronization.
In the default control scheme, the left joystick controls linear velocity, and the right joystick controls angular velocity. Holding down the RB button is required to send motion commands — otherwise, the robot will remain stationary.
On the hackerboard configuration page, under Motor-Encoder Settings, select Robot Velocities Control Mode and click Save.
A basic open-loop controller was implemented to command the Puzzlebot to move between predefined waypoints. The controller publishes linear and angular velocities directly for specific durations.
You can configure a path in puzzlebot_control/config/open_loop_point_controller_config.yaml
. Each waypoint should define its x
and y
coordinates and either a target duration or a pair of speed commands. Two modes are available:
-
Time-based mode: specify
total_time
per waypoint to automatically compute the required linear and angular velocities. -
Speed-based mode: specify
lin_speed
androt_speed
per waypoint, and the system will compute the required duration.
In both modes, it is necessary to specify min_linear_speed
, max_linear_speed
, min_angular_speed
, max_angular_speed
, and a drift_margin
. The drift margin subtracts an extra quantity an extra quantity to each command to improve robustness against drift.
This system is composed of two nodes:
- puzzlebot_control/open_loop_path_generator
: processes waypoint configurations and generates motion commands, publishing OpenLoopPose
messages containing linear velocity, angular velocity, and execution time for each movement phase.
- puzzlebot_control/open_loop_point_controller
: subscribes to OpenLoopPose
commands and executes them using a finite state machine, publishing Twist
messages to the cmd_vel
topic to drive the robot.
To execute the controller:
ros2 launch puzzlebot_control open_loop_point_controller.launch.py
Example – Time-based Mode
open_loop_path_generator:
ros__parameters:
update_rate: 10.0
waypoints_json: |
[
{ "x": 0.0, "y": 0.25, "total_time": 5.0 },
{ "x": -0.25,"y": 0.0, "total_time": 5.0 },
{ "x": -0.5, "y": 0.25, "total_time": 5.0 },
{ "x": -0.5, "y": 0.0, "total_time": 5.0 }
]
min_linear_speed: 0.1
max_linear_speed: 0.17
min_angular_speed: 0.1
max_angular_speed: 1.0
drift_margin: 0.0
open_loop_point_controller:
ros__parameters:
update_rate: 100.0
Example – Speed-based Mode
open_loop_path_generator:
ros__parameters:
update_rate: 10.0
waypoints_json: |
[
{ "x": 0.6, "y": 0.0, "lin_speed": 0.15, "rot_speed": 0.8 },
{ "x": 0.6, "y": -0.6, "lin_speed": 0.15, "rot_speed": 0.8 },
{ "x": 0.0, "y": -0.6, "lin_speed": 0.15, "rot_speed": 0.8 },
{ "x": 0.0, "y": 0.0, "lin_speed": 0.15, "rot_speed": 0.8 }
]
min_linear_speed: 0.1
max_linear_speed: 0.17
min_angular_speed: 0.1
max_angular_speed: 1.0
drift_margin: 0.0
open_loop_point_controller:
ros__parameters:
update_rate: 100.0
A PID controller was developed to improve accuracy using feedback from the robot's odometry.
The system consists of three nodes:
- puzzlebot_control/odometry_localization
: estimates the robot's pose (x, y, theta) using dead reckoning from wheel encoder data, publishing odometry messages and TF transforms.
- puzzlebot_control/pid_path_generator
: serves waypoints through a service interface, providing sequential target positions to the controller upon request.
- puzzlebot_control/pid_point_controller
: implements PID control logic to compute velocity commands, minimizing position and heading errors between current pose and target waypoint.
You can configure the system parameters in puzzlebot_control/config/pid_point_controller_config.yaml
.
The configuration includes robot physical parameters (wheel base and radius), PID controller gains for both linear and angular velocities, position and heading tolerances for waypoint completion, and velocity limits. Waypoints are defined as a JSON array of x and y coordinates, with distance constraints between consecutive points.
To launch the controller:
ros2 launch puzzlebot_control pid_point_controller.launch.py
A decision-making layer was integrated into the previously developed point-to-point PID navigation algorithm to detect and respond to traffic light colors.
The expected behavior follows standard traffic light conventions:
- Green: Continue normal path execution at full speed.
- Yellow: Reduce speed significantly until transitioning to red.
- Red: Stop and remain stationary until a green light is detected.
- No detection: Stop as a safety measure until valid color detection resumes.
Visual decision-making capabilities are implemented through two additional nodes that work alongside the existing PID navigation system:
- puzzlebot_vision/color_blob_detection
: processes camera images using HSV color filtering and morphological operations to identify red, green, and yellow traffic light blobs, publishing ColorBlobDetection
messages containing the largest detected blob's color.
- puzzlebot_behavior/traffic_light_fsm
: contains a finite state machine that uses ColorBlobDetection
messages to manage traffic light transitions and executes their corresponding actions. For green, it resumes the PID controller and scales its linear velocity control output to 100%, whereas for yellow, it scales the signal to <100% for slower movement; for red and no detection, it stops the PID controller entirely. All of these actions are executed through service calls.
You can configure the system parameters in puzzlebot_bringup/config/traffic_light_pid_point_config.yaml
.
The configuration includes HSV color ranges, image processing and blob detection parameters for traffic light identification, velocity scaling factors for green and yellow states, plus all the standard PID controller and odometry parameters from the previous system.
To run the system:
ros2 launch puzzlebot_bringup traffic_light_pid_point.launch.py
A line following layer was added to the previously developed traffic light decision solution.
Path tracking is accomplished through two additional nodes that work alongside the existing image identification system:
- puzzlebot_vision/line_detection
: processes camera images using perspective transformation and image filtering to detect lane markings, then calculates the lane's centroid position and outputs normalized lateral error indicating how far the robot deviates from the lane center.
- puzzlebot_control/line_follow_controller
: receives lateral error measurements from the detection node and uses PID control to steer the robot back toward the lane center, maintaining constant forward speed.
You can configure the system parameters in puzzlebot_bringup/config/traffic_light_line_following_config.yaml
.
The configuration includes perspective transformation points for bird's eye view mapping, image processing values for lane detection, constant linear velocity for lane tracking, PID gains for lateral control, timeout value for stopping operation when lane is temporarily lost, steering deadband threshold (a tolerance to reduce small steering oscillations), plus all parameters from the previous system.
To run the system:
ros2 launch puzzlebot_bringup traffic_light_line_following.launch.py