This project is an open-source implementation of a SLAM (Simultaneous Localization and Mapping) robot.
All CAD and software is contained within this repo.
- Omnidirectional movement using 4 dual-layer omniwheels
- Report odometry accurate to 3cm at 8ft range
- Last test: 12/20/2025 with 0.5% error in forward odom, within 3% error for side movement when moving 8ft straight. And 3cm off-center drift when doing pure diagonal.
- Real-time mapping (SLAM Toolbox)
- Autonomous navigation (Nav2)
- High-precision stepper-based odometry
- 4x NEMA 17 Stepper Motors: 0.25kg each = 1.0kg total
- 4x 60mm Omni wheels: 0.1kg each = 0.4kg total
- 1x 6000mAh Lipo battery: 0.55kg
- 1x NVIDIA Jetson Xavier NX: 0.2kg
- 1x Intel RealSense D455: 0.3kg
- 3x Chassis plates: 0.3kg total
- 1x RPLIDAR A1: 0.2kg
Total weight: 3.5kg rounded
- Speed: 0.3 m/s
- Acceleration: 0.5 m/s²
- Max payload: 3.5 kg
- Wheels: 60mm (0.0297m radius) omni wheels in 90° configuration
- Worst case surface: Concrete (Rolling resistance ~0.03)
- Torque safety factor: 2
This gives us the total torque required for the robot to meet our acceleration target. However, we need the worst-case torque per motor. One might assume it splits evenly between two motors when moving forward/backward or left/right. But could diagonal movement need more?
If each motor provides torque
- NEMA 17 Stepper Motors paired with an Arduino CNC Shield
- 800 steps/rev (1/4 microstepping)
Driver:
- A4988 or DRV8825 drivers
- Up to 2A current capability
Steppers provide high holding torque and precise positioning without needing external encoders. While they don't have current sensing, the open-loop nature of steppers is offset by our odometry integration.
- Voltage: 12V (3S Lipo)
- Desired Runtime: 1 hour
- Motors: 0.4A each → 1.6A total
- Jetson Xavier NX: ~15W @ 12V → 1.25A
- RealSense D455: ~3.5W @ 5V → ~0.35A at 12V side
- RPLIDAR A1: ~100mA
To run for 1 hour:
Our 6000mAh battery is more than sufficient, providing a significant safety margin.
We use inverse kinematics to command motor speeds from a target chassis twist and forward kinematics to compute odometry.
Where:
$r = 0.0297\text{m}$ $R = 0.1325\text{m}$ $\gamma = 0$
Simplified implementation (motor_controller.ino):
v_{Front} = -(v_y + R * omega)
v_{Left} = (v_x - R * omega)
v_{Back} = (v_y - R * omega)
v_{Right} = -(v_x + R * omega)
The motor_controller.ino uses the MobaTools library for smooth, ramped stepper control.
- Serial Parsing: Reads
$v_x$ ,$v_y$ ,$\omega$ at 40Hz - Speed Clamping: Ensures steps/sec never exceed STEPS_PER_SEC_MAX (2000 steps/s)
- Odometry Integration: Calculates and broadcasts
$x$ ,$y$ , yaw over serial
The main.py node handles the Jetson-to-Arduino communication:
- Command Forwarding: Converts ROS Twist messages into serial strings
- Odometry Publishing: Publishes nav_msgs/Odometry with appropriate covariances
Fully integrated with Nav2.
nav2_params.yaml limits:
max_vel_x: 0.25 m/s
max_vel_theta: 1.5 rad/s
This ensures reliable stepper performance without missing steps during complex maneuvers.
MIT License

