EduBot is a ROS 2 package that provides robot description, drivers, and bringup for the EduBot platform. It includes:
- Serial bridge to the PRIZM motor controller
- Wheel odometry
- IMU integration and Madgwick filter
- USB camera support
- 2D LiDAR driver
- EKF-based odometry
- SLAM Toolbox
This README assumes you are using Ubuntu 24.04 and ROS 2 Jazzy.
- Target OS: Ubuntu 24.04 (Noble Numbat)
- Target ROS 2: Jazzy Jellyfish (desktop)
- Python: system Python 3.12
# Source the ROS 2 setup in every new shell (or add to your shell rc):
source /opt/ros/jazzy/setup.bash
# Initialize rosdep (only the first time):
sudo rosdep init
rosdep update
# Create a ROS workspace if you haven't and clone the edu packages into ~/ros2_ws/src:
mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
# Main robot package
git clone https://github.com/Aeolus96/edubot.git
# IMU serial publisher (optional for EduBot)
git clone https://github.com/Aeolus96/imu_serial_to_ros_publisher.git# From the workspace root run:
cd ~/ros2_ws
rosdep update
rosdep install --from-paths src --ignore-src -r -yNOTE:
rosdepmaps package dependencies declared inpackage.xmlto system packages. It will try to install ROS packages (via apt) and system libraries. For Python packages, rosdep will either install apt-packaged Python libraries or you may need to install withpip(see next step). Some packages may need to be manually installed withaptas well.
# For installing Python packages with `pip` use a virtual environment (recommended for Ubuntu 24.04):
# Create a virtual environment named `jazzy`
cd ~/
python3 -m venv jazzy --system-site-packages
# Activate the virtual environment by sourcing the `activate` script
source ~/jazzy/bin/activate
# The `edubot` package includes a `requirements.txt` file. Install it with pip:
python3 -m pip install -r src/edubot/requirements.txt
# Now install these apt packages specific to our ROS 2 distro to make sure all package dependencies are met:
sudo apt install ros-jazzy-hls-lfcd-lds-driver* ros-jazzy-navigation2 ros-jazzy-nav2-* ros-jazzy-usb-cam* ros-jazzy-robot-state-publisher* ros-jazzy-joint-* ros-jazzy-xacro ros-jazzy-imu-* ros-jazzy-robot-localization* ros-jazzy-teleop-t* ros-jazzy-tf2* ros-jazzy-rqt* ros-jazzy-rviz* ros-jazzy-laser* ros-jazzy-sick-scan-xd*IMPORTANT: Always run the next commands from the workspace root as shown. If you run it from anywhere else, it will not work and it will create a broken workspace. To fix, remove all
build,installandlogfolders from the workspace. Re-open the terminal and run the command from the workspace root.
# Then build and source the workspace (this will be necessary commands if you make any changes to the code):
cd ~/ros2_ws
colcon build --symlink-install
# Then source the workspace to use the packages in that workspace:
source ~/ros2_ws/install/setup.bashIf you plan to use the same workspace often, add the source line to your ~/.bashrc file. You can also create aliases in the ~/.bashrc file for common commands used very often with ROS2
alias ros2_source="source ~/ros2_ws/install/setup.bash"
alias ros2_build="cd ~/ros2_ws && colcon build --symlink-install && ros2_source"
# Now you can directly type `ros2_source` or `ros2_build` in the terminal to execute the aliased commandsThis will make it easier to build and source the workspace when making changes to the code that needs compilation.
EduBot uses stable symlinks for devices so launch files don't depend on volatile /dev/ttyUSB* names when multiple devices are connected. Expected device paths are:
- PRIZM motor controller:
/dev/edubot_prizm - 2D LiDAR:
/dev/edubot_lidar - USB camera:
/dev/edubot_camera - IMU:
/dev/edubot_imu
Create these links with the interactive helper script shipped in the edubot package:
cd ~/ros2_ws/src/edubot
# Option 2 in this interactive script is recommended and it automatically adds `edubot_` before the symlink
python3 edubot_udev_setup.py
# then reload udev rules and trigger (requires replugging devices to take effect):
sudo udevadm control --reload
sudo udevadm trigger
# After replugging devices wait a few seconds, then verify links exist:
ls -l /dev/edubot_*
# Also ensure your user is in the proper groups:
sudo usermod -aG dialout $USER # serial devices
sudo usermod -aG video $USER # cameras
# then log out and back in (or reboot)From any workspace sourced shell run one of the provided launch files:
# Start entire robot's ROS 2 stack with default parameters
ros2 launch edubot edubot.launch.py
# Start robot stack with SLAM enabled for online mapping
ros2 launch edubot edubot.launch.py slam:=True
# Start with pre-built map for localization only
ros2 launch edubot edubot.launch.py slam:=False map:=/path/to/map.yamledubot.launch.py— Main launch file; starts all robot subsystems (serial bridge, odometry, LiDAR, camera, EKF, and navigation)bridge.launch.py— Launches the serial bridge (edubot_serial_bridge) and wheel odometry node (edubot_wheel_odom)description.launch.py— Launchesrobot_state_publisherandjoint_state_publisherfor robot URDF and transformsnav2_bringup_launch.py— Navigation2 configuration with support for SLAM or localization modesnav2_slam_launch.py— Launches SLAM Toolbox for online mappingnav2_localization_launch.py— Launches Nav2 localization against a pre-built mapnav2_navigation_launch.py— Launches Nav2 navigation stack
-
edubot_serial_bridge— Manages communication with PRIZM motor controller over serial (COBS protocol)- Subscribes:
/cmd_vel(geometry_msgs/Twist) - Publishes:
/joint_states(sensor_msgs/JointState),/battery_state(sensor_msgs/BatteryState)
- Subscribes:
-
edubot_wheel_odom— Computes odometry from wheel encoders using differential drive kinematics- Subscribes:
/joint_states(sensor_msgs/JointState) - Publishes:
/wheel/odometry(nav_msgs/Odometry), broadcastsodom→base_linkTF transform
- Subscribes:
-
usb_cam_node— Publishes video stream from USB camera- Publishes:
/image_raw(sensor_msgs/Image),/camera_info(sensor_msgs/CameraInfo)
- Publishes:
-
sick_tim_5xx— 2D LiDAR driver (SICK TiM561)- Publishes:
/scan(sensor_msgs/LaserScan)
- Publishes:
-
IMU publisher node — From
imu_serial_to_ros_publisherpackage (if installed)- Publishes:
imu/data_raw(sensor_msgs/Imu)
- Publishes:
-
imu_filter_madgwick— Fuses raw IMU data using Madgwick filter- Subscribes:
imu/data_raw - Publishes:
imu/data(sensor_msgs/Imu)
- Subscribes:
-
ekf_node(robot_localization) — Fuses odometry from wheels, IMU, and other sensors- Subscribes:
/wheel/odometry,imu/data - Publishes:
/odometry/filtered(nav_msgs/Odometry), broadcastsodom→base_linkTF
- Subscribes:
-
robot_state_publisher— Publishes robot URDF and static transforms- Publishes:
/robot_description,/tf_static
- Publishes:
-
joint_state_publisher— Visualizes joint angles in RViz -
Nav2 nodes — Navigation2 stack for autonomous navigation
- Includes planners, controllers, and recovery behaviors
config/camera_info.yaml— Camera calibration data (intrinsics and distortion)config/camera_params.yaml— USB camera driver parameters (resolution, frame rate, etc.)config/nav2_params.yaml— Navigation2 stack parameters (costmaps, planners, controllers)config/ekf.yaml— EKF (Extended Kalman Filter) node configuration for sensor fusionconfig/imu_filter.yaml— Madgwick IMU filter parametersconfig/scan_filter.yaml— Laser scan filter configuration
urdf/edubot.urdf— Robot URDF model defining kinematics, links, joints, and collision geometrymeshes/— Visual 3D mesh files for RViz visualizationrviz/edubot.rviz— Pre-configured RViz layout and visualization settings
maps/m215a_saved_map.yaml— Navigation2 map metadatamaps/m215a_saved_map.pgm— Occupancy grid map imagemaps/m215a_serialized_map.posegraph— SLAM Toolbox pose graph (for loop closure)
Created by Devson Butani, 2025
MIT License. See LICENSE file for details.
Contributing bug fixes and new features? Submit a pull request!