Skip to content

rigbetellabs/tortoisebot_pro

Repository files navigation

Tortoisebot Pro

ROS1 Noetic Release

tortoisebotpromax Logo

Welcome to the official public repository for TortoisebotPro by RigBetel Labs.

Purpose:
This repository hosts essential documentation and code for TortoisebotPro Robot, facilitating transparency and collaboration.

Privacy:
Certain sensitive packages and scripts have been excluded to maintain privacy standards.

Contents:

  • Documentation: Detailed guides and technical specifications.
  • Codebase: Essential source code for TortoisebotPro Robot.
  • Resources: Supplementary materials and dependencies.

Contact:
For inquiries and collaboration opportunities, reach out to RigBetel Labs.

Website Youtube Subscribers Instagram

Table of Contents
  1. Installation
  2. Connection
  3. Package Description
    1. tortoisebotpro_control
    2. tortoisebotpro_description
    3. tortoisebotpro_firmware
    4. tortoisebotpro_gazebo
    5. tortoisebotpro_navigation
    6. tortoisebotpro_odometry
    7. tortoisebotpro_slam
    8. install.sh
  4. Launch Sequence
    1. Gazebo Simulation
      1. Map Generation
      2. Autonomous Navigation in the saved map
      3. SLAM
    2. Actual Robot
      1. Map Generation
      2. Autonomous Navigation in the saved map
      3. SLAM
  5. General Robot Information
    1. Topic Description
    2. Battery
    3. Robot Velocities
    4. USB Ports

1. Installation

Clone the repository into your workspace,

cd ~/catkin_ws/src # Assuming catkin_ws is the name of the workspace
git clone https://github.com/rigbetellabs/tortoisebot_pro.git

Build the workspace,

cd ~/catkin_ws/
catkin_make

Installation of dependent packages,

cd ~/catkin_ws/src/tortoisebot_pro
cat requirements.txt | xargs sudo apt-get install -y 
# This installs all the packages mentioned in the requirements.txt

Note

Check if you already have the lidar packages installed; if not, get the packages from repos below.

cd ~/catkin_ws/src/
git clone https://github.com/YDLIDAR/ydlidar_ros_driver.git

2. Connection

Wifi Setup?

To start any operation within the robot we need to SSH into and then perform operations.

Note

After switching the robot ON the Computing device takes a minute or so to boot up, wait for a while and then SSH into the robot using the below credentials.

ssh "your-robot-name"@"your-robot-ip"

Note

Please refer the robot for robot_name and the login password. Verify the IP that gets assigned to the robot via your network manager.

If you do not want to recheck if robot is connected to the network now or then you can utilize the connect_tortoisebotpro.sh script.

./connect_tortoisebotpro.sh "username" "robot-ip"

The scripts scan the local network you are connected to and initiates a SSH connection if the robot is connected, the process continues until the robot is connected.

Successful execution looks something like this.

3. Package Description

Important

We have tested mapping and navigation using Gmapping and Cartographer, Cartographer has some inherent flaws hence we prefer to use Gmapping over Cartographer. Launch files for cartographer are provided for you to experiment. Description for these launch files are provided but the launch sequence for these lauch file has not been added.

To manually control the robot.

File Description Nodes Launched
tortoisebotpro_teleop_joy.launch Manually control the robot using Xbox controller. /joy_node, /teleop_twist_joy from tortoisebotpro_control
tortoisebot_teleop_key.py Modified version of teleop_twist_keyboard from teleop_twist_keyboard. /teleop_twist_keyboard
tortoisebotpro_teleop_joy.cpp Custom remapping from joy to cmd_vel for controlling the robot using an Xbox controller. /teleop_joy

Holds the robot description including urdf, stl, config files for rviz and gazebo

File Description Nodes Launched
display.launch Visualize the URDF of the robot in RVIZ. /rviz, /robot_state_publisher, /joint_state_publisher
gazebo.launch Visualize the Robot in an empty world within Gazebo. /gazebo, /robot_state_publisher
rviz.launch Just RVIZ, useful to visualize while mapping or navigation. /rviz

As the name suggest get all the sensor and actuation topics available to you

File Description Nodes Launched
bringup.launch Launches Robot state publishers, serial node for communication with ESP32, Lidar driver, USB can driver. /robot_state_publisher, /rosout, /serial_node, /usb_cam, /wheel_odom, /ydlidar_node
fake_landmark.py Publish fake landmarks to be used by Cartographer. /landmark_sampler
odom_pub.py Takes the odom from TF published by Cartographer and publishes it as an individual topic. Only required when used with a real robot. /odom_publisher
ticks_to_odom.py Publishes Robot odometry as perceived by wheel encoders. /wheel_odom
wavepoints.py Makes robot traverse from one point to another. /csv_to_goal_publisher

Simulation environment for tortoisebotpro in Gazebo

File Description Nodes Launched
tortoisebotpro_docking.launch Docking environment for charging. /spawn_urdf, /joint_state_publisher, /robot_state_publisher, /gazebo
tortoisebotpro_empty_world.launch Just an empty world. /spawn_urdf, /joint_state_publisher, /robot_state_publisher, /gazebo
tortoisebotpro_playground.launch Tortoisebot needs a house to live in. /spawn_urdf, /joint_state_publisher, /robot_state_publisher, /gazebo

Autonomous navigation of robot using move_base in a know as well as unknown environment

File Description Node Launched
amcl.launch Let's localize the robot in the environment, not always robot know where it is in the environment. /amcl
move_base.launch The node responsible to get the robot moving from one point to other avoiding dynamic as well as static obstacles.
Parameters for the move_base can be found in param directory
/move_base
tortoisebotpro_navigation.launch Launches move_base along with presaved map or online map generation using OR

roslaunch tortoisebotpro_odometry tortoisebotpro_carto_odom.launch/gmapping based upon your preference.
If parameter exploration with the launch file is set true then the map is provided by the mapping agent - cartographer/gmapping else offline map stored in the map directory of the tortoisebotpro_navigation package is used. Which map you may ask well set the parameter map_file to the map that will be used.
To switch mapping agent from gmapping to cartographer while in exploration set using_gmapping param to false.

/slam_gmapping, /cartographer_occupancy_grid_node, /map_server, /rviz, /move_base

How will the robot know where it is in the environment? Well it generates its own odometry for the purpose.

File Description Nodes Launched
tortoisebotpro_icp_odom.launch Produces odometry data for the robot using Lidar and IMU. /icp_odometry /ekf_localization_node, /alpha_beta_filter
tortoisebotpro_carto_odom.launch Produces odometry data for the robot using cartographer. /cartographer_node
alpha_beta_filter.py Alpha beta filter to smoothen out the translation in x and y. Odometry generated is purely based on lidar and IMU. This is how we do it. /alpha_beta_filter

TF of odom is broadcasted by alpha_beta_filter for mapping agents.

SLAM!

File Description Node Launched
gmapping.launch To generate the map of the environment using Gmapping. NOTE: Gmapping requires /scan topic as well odom => base_link transform.
Parameters for the Gmapping can be found in config directory.
/slam_gmapping
cartographer.launch To generate the map of the environment using Cartographer. /cartographer_node
map_saver.launch A map generated should be saved for navigation. /map_saver

3.8 install.sh

Performs,

  • Installation of udev rules to hardcode the physical USB ports

We have installed everything for you no need to worry about!

4. Launch Sequence

4.1 Gazebo Simulation

4.1.1 Map Generation

roslaunch tortoisebotpro_gazebo tortoisebotpro_docking.launch # To launch Gazebo simulation environment

roslaunch tortoisebotpro_slam gmapping.launch # To generate Map
roslaunch tortoisebotpro_description rviz.launch # To visualize the map generated

rosrun tortoisebotpro_control tortoisebot_teleop_key.py # To control the robot using keyboard

Save the map after satisfaction,

roslaunch tortoisebotpro_slam map_saver.launch map_name:=your_map  # To save the map
# Change your_map to what ever you want

4.1.2 Autonomous Navigation in the saved map

roslaunch tortoisebotpro_gazebo tortoisebotpro_docking.launch # To launch Gazebo simulation environment
roslaunch tortoisebotpro_navigation tortoisebotpro_navigation.launch exploration:=false map_file:=docking 

4.1.3 SLAM

roslaunch tortoisebotpro_gazebo tortoisebotpro_docking.launch # To launch Gazebo simulation environment
roslaunch tortoisebotpro_navigation tortoisebotpro_navigation.launch exploration:=true

4.2 Actual Robot

Note

For every command to be executed within the robot a new SSH connection needs to be established.

4.2.1 Map Generation

roslaunch tortoisebotpro_firmware bringup.launch using_joy:=true # Set to true if using Xbox controller to control the robot

Important

The current bringup.launch file looks for YDLidar X4-Pro model to start the scanning, if you have X4 model on your robot, edit the launch file from X4-Pro.launch to X4.launch in bringup.launch

rosrun tortoisebotpro_control tortoisebot_teleop_key.py # If using computer keyboard to control the robot

Note

If you are using XBOX controller to control the robot set the using_joy argument within the bringup.launch to true and donot use tortoisebot_teleop_key.py and if teleop_twist_keyboard set the using_joy argument within the bringup.launch to false and execute tortoisebot_teleop_key.py

Config to use the XBOX controller

roslaunch tortoisebotpro_odometry tortoisebotpro_icp_odom.launch # TO generate Odometry
roslaunch tortoisebotpro_slam gmapping.launch # To generate Map

Save the map after satisfaction,

roslaunch tortoisebotpro_slam map_saver.launch map_name:=your_map 
# Change your_map to what ever you want

4.2.2 Autonomous Navigation in the saved map

roslaunch tortoisebotpro_firmware bringup.launch 
roslaunch tortoisebotpro_odometry tortoisebotpro_icp_odom.launch # TO generate Odometry
roslaunch tortoisebotpro_navigation tortoisebotpro_navigation.launch exploration:=false map_file:=your_map 

4.2.3 SLAM

roslaunch tortoisebotpro_firmware bringup.launch 
roslaunch tortoisebotpro_odometry tortoisebotpro_icp_odom.launch # TO generate Odometry
roslaunch tortoisebotpro_navigation tortoisebotpro_navigation.launch exploration:=true

Tip

For you to visualize the maps, robot position you will need to connect robot and your computer in a ROS_MASTER and ROS_SLAVE configuration. Follow the below instructions to do so

Open a terminal editor to edit .bashrc

nano ~/.bashrc

Paste the below code with right credentials

export ROS_MASTER_URI=http://"your-robot-ip":11311
export ROS_HOSTNAME="your-computer-ip"

How to find your computer ip,

hostname -I

And then launch,

roslaunch tortoisebotpro_description rviz.launch # To visualize the map generated

5. General Robot Information

Parameter Value
Wheel Separation Length 0.195m
Motor Type Planetary DC Geared Motor
RPM 110
Encoder Type Magnetic Encoder
PPR (Pulses Per Revolution) 420
Microcontroller DOIT-ESP32 Devkit V1
PC Used Intel NUC i3 10th Gen
Robot Payload Capacity 15 kgs
Battery Life About 1.5 hours
Battery Type Lithium-ion 6-cell, 22.2V

5.1 Topic Description

Topic Description
/bat_per Battery percentage remaining until complete discharge
/bat_voltage Battery voltage
/cmd_vel Command velocity for the robot
/diagnostics Diagnostics messages
/heading Robot heading based on magnetometer
/imu/data IMU data including orientation, rotational velocities and linear acceleration
/wheel/ticks Encoder reading of wheels in an array of the format of [left, right]
/wheel/vel Wheel velocities in an array of the format of [left, right]
/odom Odometry generated from wheel encoders
/pid/constants Set PID constants
/pid/control Should PID be used or not
/scan Lidar measurements
/usb_cam Cascaded topics providing complete information about the camera
/diagnostics/test Run diagnostics on the robot

5.2 Battery

Within the robot a buzzer beeps to indicate the status of battery.

Battery Level Beeps Status
100 % to 20 % No beeps
20 % to 15 % Beeps after every 2 mins
15 % to 10 % Beeps after every 1 min
10 % to 0 % Continuous Beeps

Caution

Do not drain the battery below 10 %, doing so will damage the battery permanently. Maximum battery voltage is 25.2V and minimum usable battery voltage is 19.8V

A battery is made available on the robot which indicate the status of the battery so that you don't have to echo on topics. Every bar on the indicator indicates 25% battery health. So,

Bar Level Battery Level
1 0 % to 25 %
2 25 % to 50 %
3 50 % to 75 %
4 75 % to 100 %

5.3 Robot Velocities

Maximum Linear Velocity - 0.37 m s-1
Maximum Angular Velocity - 3.836 rad s-1

5.4 USB Ports

A strict rule needs to be followed while connecting Lidar, ESP32 and USB camera. These ports are hardcoded and devices needs to be connected as depicted below.

About

No description, website, or topics provided.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published