(AMR) Autonomous Mobile Robotics Cleaning Robot

Autonomous mobile robot for indoor cleaning, built with ROS (Noetic), Webots, and RViz. Features SLAM, navigation, trajectory planning, and dynamic obstacle avoidance.

GitHub GitHub Repository

Introduction

Welcome to the Cleaning Robot project. It simulates an autonomous cleaning AMR on Ubuntu 20.04 using ROS1 Noetic, Webots, and RViz.

Key Capabilities

  • SLAM: Builds a detailed map using Lidar and odometry for obstacle-aware navigation.
  • Planning Trajectories: Uses NavfnROS and TrajectoryPlannerROS to compute optimal global/local paths accounting for static and dynamic obstacles.
  • Dynamic Obstacle Avoidance: Sensors and planners cooperate to steer around obstacles for smooth navigation.

Home Environment

The robot operates in a Webots home world, showing both top view and onboard camera.

Home environment

Robot Structure & URDF

Rectangular mobile base with linear and rotary actuators for camera positioning; equipped with distance sensors, dual GPS, Lidar, and IMU. Fixed joints for body-mounted components; continuous joints for actuators/camera. URDF is generated from the CleaningRobot.xacro via robot_description, published by robot_state_publisher.

Robot structure

URDF graph (rqt):

URDF scheme

Verify with:

rosrun rqt_gui rqt_gui
rqt graph

TeleOp (Keyboard)

Keyboard teleoperation to drive the robot and orient the camera.

TeleOp

To monitor TeleOp topic while running:

  • rostopic list โ†’ find /Cam_robot_xxxxxx_NameOfYourMachine
  • rostopic echo /Cam_robot_xxxxxx_NameOfYourMachine/keyboard/key

SLAM with GMapping

Builds a 2D occupancy grid and estimates pose using Rao-Blackwellized particle filter. Input: raw laser + odometry; outputs map and pose.

SLAM Building Instructions

  • Checkout SLAM branch: git checkout SLAM_Map_Building
  • Terminal 1: catkin build, source devel/setup.bash, roslaunch bringup master.launch
  • Terminal 2: run GMapping (replace topic with your scan):
    rosrun gmapping slam_gmapping scan:=/Cam_robot_xxxx_Ubuntu_22_04/Lidar/laser_scan/layer0
SLAM Building Demo
SLAM building

Saving the Map

Use map_server to save:
rosrun map_server map_saver -f src/robot_settings/maps/map

SLAM result

The AMR navigates with a Global Path (NavfnROS, Dijkstra) over the global costmap and a Local Path (TrajectoryPlannerROS) for obstacle avoidance. MoveBase orchestrates maps, planners, and cmd_vel.

Set a goal in RViz (2D Nav Goal); the robot plans and follows, handling new obstacles.

Navigation & Planning Demo
Navigation & planning
Obstacle Avoidance Demo
Object avoidance

Recovery: MoveBase will rotate and retry; if unsolvable it cancels. Clear noisy data via:
rosservice call /move_base/clear_costmaps

Noisy map clearing

Setup & Launch (Installation)

  1. Installations
  2. Workspace Setup
    • mkdir nameFolder && cd nameFolder
    • mkdir -p CleaningRobot_ws/src && cd CleaningRobot_ws/src
    • git clone https://github.com/alessioborgi/CleaningRobot_RP.git
  3. Dependencies and Packages Installation
    • In the workspace: sudo apt-get install python3-rosdep
    • sudo rosdep init
    • rosdep update
    • cd robot_settings then rosdep install --from-paths src --ignore-src -y
    • cd .. then cd nav_plan_objavoid and run rosdep install --from-paths src --ignore-src -y
  4. Launching the Project
    • cd nameFolder/CleaningRobot_ws
    • catkin build
    • source devel/setup.bash
    • roslaunch robot_settings master.launch (opens Webots + RViz)

Other Project