Welcome to DiffBot Documentation
This project guides you on how to build an autonomous two wheel differential drive robot.
The robot can operate on a Raspberry Pi 4 B or NVIDIA Jetson Nano Developer Kit
running ROS Noetic or ROS Melodic middleware on Ubuntu Mate 20.04 and Ubuntu 18.04, respectively.
With a motor driver that actuates two brushed motors the robot can drive autonomously to a desired location while sensing its environment using sensors,
such as a laser scanner to avoid obstacles and a camera to detect objects. Odometry wheel encoders (also refered to as speed sensors)
combined with an inertial measurement unit (IMU) are used together with the laser scanner for localization in a previously stored map.
Unseen enviornments can be mapped with the laser scanner, making use of open source SLAM algorithms such as gmapping
.
The following video gives an overview of the robot's components:
The project is split into multiple parts, to adress the following main aspects of the robot.
- Bill of Materials (BOM) and the theory behind the parts.
- Theory of (mobile) robots.
- Assembly of the robot platform and the components.
- Setup of ROS (Noetic or Melodic) on either Raspberry Pi 4 B or Jetson Nano, which are both Single Board Computers (SBC) and are the brain of the robot.
- Modeling the Robot in Blender and URDF to simulate it in Gazebo.
- ROS packages and nodes:
- Hardware drivers to interact with the hardware components
- High level nodes for perception, navigation, localization and control.
Use the menu to learn more about the ROS packages and other components of the robot.
Note
Using a Jetson Nano instead of a Raspberry Pi is also possible. See the Jetson Nano Setup section in this documentation for more details. To run ROS Noetic Docker is needed.
Source Code
The source code for this project can be found in the ros-mobile-robots/diffbot GitHub repository.
Remo Robot
You can find Remo robot (Research Education Modular/Mobile Open robot), a 3D printable and modular robot description package available at ros-mobile-robots/remo_description. The stl files are freely availabe from the repository and stored inside the git lfs (Git large file system) on GitHub. The bandwith limit for open source projects on GitHub is 1.0 GB per month, which is why you might not be able to clone/pull the files because the quota is already exhausted this month. To support this work and in case you need the files immediately, you can access them through the following link:
Best Practices and REP
The project tries to follow the ROS best practices as good as possible. This includes examples and patterns on producing and contributing high quality code, as well as on testing, and other quality oriented practices, like continuous integration. You can read more about it on the ROS Quality wiki. This includes also following the advices given in the ROS Enhancement Proposals (REPs). Throughout the documentation links to corresponding REPs are given.
The wiki section ROS developer's guide is a good starting point for getting used to the common practices for developing components to be shared with the community. It includes links to naming conventions (e.g. for packages) and ROS C++ and Python style guides.
Other good resources to learn more about ROS best practices is the Autonomous Systems Lab of ETH Zurich.
Note
Your contributions to the code or documentation are most welcome but please try to follow the mentioned best pratices where possible.
Testing, Debugging and CI
For a ROS catkin workspace explaining gTest and rostest see Ros-Test-Example and its documentation. To run tests with catkin-tools, see Building and running tests.
To get a workspace that allows a debugger to stop at breakpoints, it is required to build the catkin workspace with Debug Symbols.
For this the command catkin build --save-config --cmake-args -DCMAKE_BUILD_TYPE=Debug
is used, mentioned in the catkin-tools cheat sheet.
This repository makes use of automated builds when new code is pushed or a pull reuqest is made to this repository. For this the Travis and GitHub actions configurations (yml files) from ROS Industrial CI are used.
Documentation
The documentation is using material design theme, which is based on MkDocs. Future code documentation will make use of doxygen and rosdoc_lite.
References
Helpful resources to bring your own robots into ROS are:
- Understand ROS Concepts
- Follow ROS Tutorials such as Using ROS on your custom Robot
- Books:
- Mastering ROS for Robotics Programming: Best practices and troubleshooting solutions when working with ROS, 3rd Edition this book contains also a chapter about about Remo
- Introduction to Autonomous Robots (free book)
- Robot Operating System (ROS) for Absolute Beginners from Apress by Lentin Joseph
- Programming Robots with ROS A Practical Introduction to the Robot Operating System from O'Reilly Media
- Mastering ROS for Robotics Programming Second Edition from Packt
- Elements of Robotics Robots and Their Applications from Springer
- ROS Robot Programming Book for Free! Handbook from Robotis written by Turtlebot3 Developers
- Courses: