A differential drive mobile robot simulation package for ROS2 Humble with stable ball caster design for Gazebo Ignition.
- Stable Differential Drive: 2 powered wheels with differential drive controller
- No-Hop Ball Casters: Redesigned from complex swivel casters to simple ball casters, eliminating reverse motion hopping
- Dual Format Support: Both SDF (for Gazebo) and URDF (for RViz/Nav2) formats
- Production Ready: Tested and verified in Gazebo Ignition and RViz
- Extensible Design: Ready for sensor integration (Lidar, Camera, IMU)
ros2 launch donar_robot_description gazebo_sdf.launch.pyros2 run rviz2 rviz2 -d src/donar_robot_description/rviz/urdf_config.rvizros2 run teleop_twist_keyboard teleop_twist_keyboard \
--ros-args -r /cmd_vel:=/donar_robot/cmd_vel- OS: Ubuntu 22.04
- ROS2: Humble
- Gazebo: Ignition Garden or Fortress
- Tools: Colcon, Git
# Create workspace
mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
# Clone repository
git clone https://github.com/yourusername/donar_robot_description.git
# Install dependencies
cd ~/ros2_ws
rosdep install --from-paths src --ignore-src -r -y
# Build
colcon build --packages-select donar_robot_description
# Source
source install/setup.bashLaunch Gazebo Simulation:
export GZ_SIM_RESOURCE_PATH=$GZ_SIM_RESOURCE_PATH:~/ros2_ws/install/donar_robot_description/share
ros2 launch donar_robot_description gazebo_sdf.launch.pyControl the Robot:
# Install keyboard teleop
sudo apt install ros-humble-teleop-twist-keyboard
# Run teleop
ros2 run teleop_twist_keyboard teleop_twist_keyboard \
--ros-args -r /cmd_vel:=/donar_robot/cmd_vel| Parameter | Value |
|---|---|
| Type | Differential Drive |
| Total Mass | ~40 kg |
| Wheel Radius | 0.14 m |
| Wheel Separation | 0.52 m |
| Max Linear Velocity | 3 m/s |
| Max Angular Velocity | 3.0 rad/s |
| Caster Type | Ball (40mm radius) |
| Control Interface | geometry_msgs/Twist |
donar_robot_description/
├── config/ # Controller configurations
├── launch/ # Launch files (Gazebo, RViz)
├── meshes/ # CAD-exported STL meshes
├── models/ # SDF models for Gazebo
│ └── donar_robot/
│ ├── model.config
│ └── model.sdf # Primary robot definition
├── rviz/ # RViz configurations
├── urdf/ # URDF/xacro files
└── worlds/ # Gazebo world files
Main Files:
models/donar_robot/model.sdf- Primary robot definition for Gazebourdf/donar_robot.xacro- URDF description for RViz/Nav2launch/gazebo_sdf.launch.py- Main simulation launcher
Robot Links:
base_link- Main robot chassis (35 kg)left_wheel_1,right_wheel_1- Driven wheels (2 kg each)left_caster_wheel_1,right_caster_wheel_1- Ball casters (0.4 kg each)
Topics:
/donar_robot/cmd_vel- Velocity commands (input)/donar_robot/odometry- Odometry feedback (output)/joint_states- Joint positions/velocities (output)
- Base robot model with differential drive
- Simplified ball caster design
- Gazebo Ignition integration
- RViz visualization support
- Odometry and joint state publishing
- Teleop control interface
- RPLidar A2 sensor integration
- Intel RealSense camera
- IMU sensor (for sensor fusion)
- Nav2 navigation stack integration
- SLAM capability (slam_toolbox)
- Autonomous waypoint navigation
- Gazebo world scenarios
- Hardware deployment guide
- ROS2 Tutorials: docs.ros.org
- Gazebo Documentation: gazebosim.org
- Project Wiki: Coming soon
Published Topics:
/donar_robot/odometry [nav_msgs/Odometry]
/joint_states [sensor_msgs/JointState]
/clock [rosgraph_msgs/Clock]
/tf [tf2_msgs/TFMessage]
Subscribed Topics:
/donar_robot/cmd_vel [geometry_msgs/Twist]
Parameters:
wheel_separation: 0.52
wheel_radius: 0.14
max_linear_velocity: 3
max_angular_velocity: 3.0Contributions are welcome! Please feel free to submit issues and pull requests.
# Fork the repository
# Clone your fork
git clone https://github.com/yourusername/donar_robot_description.git
# Create feature branch
git checkout -b feature/your-feature
# Make changes and commit
git commit -m "feat: add your feature"
# Push and create PR
git push origin feature/your-featureThis project is licensed under the MIT License - see the LICENSE file for details.
Dieudonne YUFONYUY
- Email: dieudonne.yufonyuy@gmail.com
- LinkedIn: [https://www.linkedin.com/in/dieudonne-yufonyuy
- ROS2 Community - For excellent documentation and support
- Gazebo Team - For powerful simulation tools
- fusion2urdf - For CAD to URDF conversion
- Open source robotics community
- Navigation2 - ROS2 Navigation Stack
- slam_toolbox - SLAM for ROS2
- gazebo_ros_pkgs - Gazebo ROS integration
⭐ If you find this project useful, please consider giving it a star!
Last Updated: December 2025