All Projects → ros-mobile-robots → diffbot

ros-mobile-robots / diffbot

Licence: BSD-3-Clause license
DiffBot is an autonomous 2wd differential drive robot using ROS Noetic on a Raspberry Pi 4 B. With its SLAMTEC Lidar and the ROS Control hardware interface it's capable of navigating in an environment using the ROS Navigation stack and making use of SLAM algorithms to create maps of unknown environments.

Programming Languages

C++
36643 projects - #6 most used programming language
CMake
9771 projects
lua
6591 projects

Projects that are alternatives of or similar to diffbot

my ROS mobile robot
Differential drive mobile robot using ROS.
Stars: ✭ 123 (-28.49%)
Mutual labels:  gazebo, rviz, ros-control
open manipulator simulations
ROS Simulation for OpenManipulator
Stars: ✭ 15 (-91.28%)
Mutual labels:  robot, gazebo
lego-mindstorms-51515-jetson-nano
Combines the LEGO Mindstorms 51515 with the NVIDIA Jetson Nano
Stars: ✭ 31 (-81.98%)
Mutual labels:  robot, jetson-nano
dofbot-jetson nano
Yahboom DOFBOT AI Vision Robotic Arm with ROS for Jetson NANO 4GB B01
Stars: ✭ 24 (-86.05%)
Mutual labels:  jetson-nano, noetic
curio
ROS packages to control a version of Roger Chen's Sawppy Rover.
Stars: ✭ 38 (-77.91%)
Mutual labels:  gazebo, ros-control
turtlebot rrt
Rapidly Exploring Random Tree (RRT) global path planning plugin for ROS Kinetic Kame
Stars: ✭ 86 (-50%)
Mutual labels:  gazebo, rviz
dd performances
DeepDetect performance sheet
Stars: ✭ 92 (-46.51%)
Mutual labels:  raspberry, jetson-nano
raspi-chatrobot
基于树莓派的微信机器人
Stars: ✭ 33 (-80.81%)
Mutual labels:  robot, raspberry
conde simulator
Autonomous Driving Simulator for the Portuguese Robotics Open
Stars: ✭ 31 (-81.98%)
Mutual labels:  robot, gazebo
anyfesto
Low cost Raspberry Pi /Linux based access point with audio, education and communications local content server. Inspired by the ideas of sharing with others. Anyfesto - a platform from which to speak.
Stars: ✭ 66 (-61.63%)
Mutual labels:  raspberry
1ZLAB PyEspCar
1ZLab在准备挑选合适的小车来研发计算机视觉的教程时候 , 发现习惯了Python语法的我们, 在市面上找不到合适小车, 后来我们选了ESP32作为小车的控制主板, 可以使用Python对其进行交互式编程, 极大的提升了开发效率.
Stars: ✭ 78 (-54.65%)
Mutual labels:  robot
Timetable-App
This is a timetable App for android phones.
Stars: ✭ 19 (-88.95%)
Mutual labels:  smart
Robot Arm Write Chinese
使用uArm Swift Pro机械臂写中文-毛笔字
Stars: ✭ 57 (-66.86%)
Mutual labels:  robot
node-lumi-aqara
Control your Xiaomi Smart Home devices with this Lumi Aqara library
Stars: ✭ 45 (-73.84%)
Mutual labels:  smart
realant
RealAnt robot platform for low-cost, real-world reinforcement learning
Stars: ✭ 40 (-76.74%)
Mutual labels:  robot
Instant-Face-Unlock
Xposed Module's InstantFaceUnlock Code
Stars: ✭ 23 (-86.63%)
Mutual labels:  smart
G-Code-Arduino-Library
Allows any machines and robots to be controlled by G-Code
Stars: ✭ 44 (-74.42%)
Mutual labels:  robot
icra20-hand-object-pose
[ICRA 2020] Robust, Occlusion-aware Pose Estimation for Objects Grasped by Adaptive Hands
Stars: ✭ 42 (-75.58%)
Mutual labels:  robot
Python-NEO-6M-GPS-Raspberry-Pi
Python script for the NEO-6M GPS module on the Raspberry Pi
Stars: ✭ 41 (-76.16%)
Mutual labels:  raspberry
teensy-midi-looper
teensy midi loop recorder
Stars: ✭ 30 (-82.56%)
Mutual labels:  teensy

DiffBot

CI Documentation CI

DiffBot is an autonomous differential drive robot with two wheels. Its main processing unit is a Raspberry Pi 4 B running Ubuntu Mate 20.04 and the ROS 1 (ROS Noetic) middleware. This respository contains ROS driver packages, ROS Control Hardware Interface for the real robot and configurations for simulating DiffBot. The formatted documentation can be found at: https://ros-mobile-robots.com.

DiffBot Lidar SLAMTEC RPLidar A2

If you are looking for a 3D printable modular base, see the remo_description repository. You can use it directly with the software of this diffbot repository.

Remo Gazebo Simulation RViz

It provides mounts for different camera modules, such as Raspi Cam v2, OAK-1, OAK-D and you can even design your own if you like. There is also support for different single board computers (Raspberry Pi and Nvidia Jetson Nano) through two changable decks. You are agin free to create your own.

Demonstration

SLAM and Navigation

Real robot Gazebo Simulation

📦 Package Overview

Installation

The packages are written for and tested with ROS 1 Noetic on Ubuntu 20.04 Focal Fossa. For the real robot Ubuntu Mate 20.04 for arm64 is installed on the Raspberry Pi 4 B with 4GB. The communication between the mobile robot and the work pc is done by configuring the ROS Network, see also the documentation.

Dependencies

The required Ubuntu packages are listed in software package sections found in the documentation. Other ROS catkin packages such as rplidar_ros need to be cloned into the catkin workspace.

For an automated and simplified dependency installation process install the vcstool, which is used in the next steps.

sudo apt install python3-vcstool

🔨 How to Build

To build the packages in this repository including the Remo robot follow these steps:

  1. cd into an existing ROS Noetic catkin workspace or create a new one:

    mkdir -p catkin_ws/src
  2. Clone this repository in the src folder of your ROS Noetic catkin workspace:

    cd catkin_ws/src
    git clone https://github.com/fjp/diffbot.git
  3. Execute the vcs import command from the root of the catkin workspace and pipe in the diffbot_dev.repos or remo_robot.repos YAML file, depending on where you execute the command, either the development PC or the SBC of Remo to clone the listed dependencies. Run the following command only on your development machine:

    vcs import < src/diffbot/diffbot_dev.repos
    

    Run the next command on Remo robot's SBC:

    vcs import < src/diffbot/remo_robot.repos
    
  4. Install the requried binary dependencies of all packages in the catkin workspace using the following rosdep command:

    rosdep install --from-paths src --ignore-src -r -y
    
  5. After installing the required dependencies build the catkin workspace, either with catkin_make:

    catkin_ws$ catkin_make

    or using catkin-tools:

    catkin_ws$ catkin build
  6. Finally, source the newly built packages with the devel/setup.* script, depending on your used shell:

    For bash use:

    catkin_ws$ source devel/setup.bash

    For zsh use:

    catkin_ws$ source devel/setup.zsh

Usage

The following sections describe how to run the robot simulation and how to make use of the real hardware using the available package launch files.

Gazebo Simulation with ROS Control

Control the robot inside Gazebo and view what it sees in RViz using the following launch file:

roslaunch diffbot_control diffbot.launch

This will launch the default diffbot world db_world.world.

To run the turtlebot3_world make sure to download it to your ~/.gazebo/models/ folder, because the turtlebot3_world.world file references the turtlebot3_world model. After that you can run it with the following command:

roslaunch diffbot_control diffbot.launch world_name:='$(find diffbot_gazebo)/worlds/turtlebot3_world.world'
db_world.world turtlebot3_world.world
corridor-world turtlebot3-world

Navigation

To navigate the robot in the Gazebo simulator in db_world.world run the command:

roslaunch diffbot_navigation diffbot.launch

This uses a previously mapped map of db_world.world (found in diffbot_navigation/maps) that is served by the map_server. With this you can use the 2D Nav Goal in RViz directly to let the robot drive autonomously in the db_world.world.

DiffBot navigation

To run the turtlebot3_world.world (or your own stored world and map) use the same diffbot_navigation/launch/diffbot.launch file but change the world_name and map_file arguments to your desired world and map yaml files:

roslaunch diffbot_navigation diffbot.launch world_name:='$(find diffbot_gazebo)/worlds/turtlebot3_world.world' map_file:='$(find diffbot_navigation)/maps/map.yaml'

DiffBot navigation

SLAM

To map a new simulated environment using slam gmapping, first run

roslaunch diffbot_gazebo diffbot.launch world_name:='$(find diffbot_gazebo)/worlds/turtlebot3_world.world'

and in a second terminal execute

roslaunch diffbot_slam diffbot_slam.launch slam_method:=gmapping

Then explore the world with the teleop_twist_keyboard or with the already launched rqt_robot_steering GUI plugin:

DiffBot slam

When you finished exploring the new world, use the map_saver node from the map_server package to store the mapped enviornment:

rosrun map_server map_saver -f ~/map

RViz

View just the diffbot_description in RViz.

roslaunch diffbot_description view_diffbot.launch

DiffBot RViz

Navigating and Mapping on the real Robot

The following video shows how to map a new environment and navigate in it

Start by setting up the ROS Network, by making the development PC the rosmaster (set the ROS_MASTER_URI environment variable accordingly, see ROS Network Setup for more details), Then follow the steps listed below to run the real Diffbot or Remo robot hardware:

  1. First, brinup the robot hardware including its laser with the following launch file from the diffbot_bringup package. Make sure to run this on the real robot (e.g. connect to it via ssh):

    roslaunch diffbot_bringup bringup_with_laser.launch
  2. Then, in a new terminal on your remote/work development machine (not the single board computer) run the slam gmapping with the same command as in the simulation:

    roslaunch diffbot_slam diffbot_slam.launch slam_method:=gmapping

    As you can see in the video, this should open up RViz and the rqt_robot_steering plugin.

  3. Next, steer the robot around manually either using the keyboard_teleop node or using the rqt_robot_steering node and save the map with the following command when you are done exploring:

    rosrun map_server map_saver -f office

After the mapping process it is possible to use the created map for navigation, after running the following launch files:

  1. On the single board computer (e.g. Raspberry Pi) make sure that the following is launched:

    roslaunch diffbot_bringup bringup_with_laser.launch
  2. Then on the work/remote development machine run the diffbot_hw.lauch from the diffbot_navigation package:

    roslaunch diffbot_navigation diffbot_hw.lauch

    Among other essential navigation and map server nodes, this will also launch an instance of RViz on your work pc where you can use its tools to:

    1. Localize the robot with the "2D Pose Estimate" tool (green arrow) in RViz
    2. Use the "2D Nav Goal" tool in RViz (red arrow) to send goals to the robot

🚧 Future Work

Contributions to these tasks are welcome, see also the contribution section below.

ROS 2

  • Migrate from ROS 1 to ROS 2

Drivers, Odometry and Hardware Interface

  • Add diffbot_driver package for ultrasonic ranger, imu and motor driver node code.
  • Make use of the imu odometry data to improve the encoder odometry using a Kalman filter, such as robot_localization (or the less active robot_pose_ekf).
  • The current implementation of the ROS Control hardware_interface::RobotHW uses a high level PID controller. This is working but also test a low level PID on the Teensy 3.2 mcu using the Arduino library of the Grove i2c motor driver. -> This is partly implemented (see diffbot_base/scripts/base_controller) Also replace Wire.h with the improved i2c_t3 library.

Navigation

  • Test different global and local planners and add documentation
  • Add diffbot_mbf package using move_base_flex, the improved version of move_base.

Perception

To enable object detection or semantic segmentation with the RPi Camera the Raspberry Pi 4 B will be upated with a Google Coral USB Accelerator. Possible useful packages:

Mseg Example

Teleoperation

Tooling

Part List Diffbot

SBC RPi 4B MCU Teensy 3.2 IMU Bosch
Part Store
Raspberry Pi 4 B (4 Gb) Amazon.com, Amazon.de
SanDisk 64 GB SD Card Class 10 Amazon.com, Amazon.de
Robot Smart Chassis Kit Amazon.com, Amazon.de
SLAMTEC RPLidar A2M8 (12 m) Amazon.com, Amazon.de
Grove Ultrasonic Ranger Amazon.com, Amazon.de
Raspi Camera Module V2, 8 MP, 1080p Amazon.com, Amazon.de
Grove Motor Driver seeedstudio.com, Amazon.de
I2C Hub seeedstudio.com, Amazon.de
Teensy 4.0 or 3.2 PJRC Teensy 4.0, PJRC Teensy 3.2
Hobby Motor with Encoder - Metal Gear (DG01D-E) Sparkfun

Part List Remo

Part Store
Raspberry Pi 4 B (4 Gb) Amazon.com, Amazon.de
SanDisk 64 GB SD Card Class 10 Amazon.com, Amazon.de
Remo Base 3D printable, see remo_description
SLAMTEC RPLidar A2M8 (12 m) Amazon.com, Amazon.de
Raspi Camera Module V2, 8 MP, 1080p Amazon.com, Amazon.de
Adafruit DC Motor (+ Stepper) FeatherWing adafruit.com, Amazon.de
Teensy 4.0 or 3.2 PJRC Teensy 4.0, PJRC Teensy 3.2
Hobby Motor with Encoder - Metal Gear (DG01D-E) Sparkfun
Powerbank (e.g 15000 mAh) Amazon.de This Powerbank from Goobay is close to the maximum possible size LxWxH: 135.5x70x18 mm)
Battery pack (for four or eight batteries) Amazon.de

Additional (Optional) Equipment

Part Store
PicoScope 3000 Series Oscilloscope 2CH Amazon.de
VOLTCRAFT PPS-16005 Amazon.de
3D Printer for Remo's parts Prusa, Ultimaker, etc. or use a local print service or an online one such as Sculpteo

Hardware Architecture and Wiring

DiffBot

Hardware Architecture and Wiring

Remo

Hardware Architecture and Wiring

🤝 Acknowledgment

🔧 Contributing

Your contributions are most welcome. These can be in the form of raising issues, creating PRs to correct or add documentation and of course solving existing issues or adding new features.

📝 License

diffbot is licenses under the BSD 3-Clause. See also open-source-license-acknowledgements-and-third-party-copyrights.md. The documentation is licensed differently, visit its license text to learn more.

Note that the project description data, including the texts, logos, images, and/or trademarks, for each open source project belongs to its rightful owner. If you wish to add or remove any projects, please contact us at [email protected].