Differences

This shows you the differences between two versions of the page.

Link to this comparison view

Both sides previous revisionPrevious revision
Next revision
Previous revision
en:ros:simulations:turtlebot [2021/03/30 09:29] – [SLAM Simulation] momalaen:ros:simulations:turtlebot [Unknown date] (current) – external edit (Unknown date) 127.0.0.1
Line 4: Line 4:
 {{ :en:ros:simulations:turtlebot_family.png?600 |}} {{ :en:ros:simulations:turtlebot_family.png?600 |}}
  
-Most recent and developed version of the turtlebot is version 3. TurtleBot3 is made up of modular plates that users can customize the shape. Available in three types: small size Burger and medium-size Waffle, Waffle Pi. TurtleBot3 consists of a base, two Dynamixel motors, a 1,800mAh battery pack, a 360 degree LIDAR, a camera(+ RealSense camera for Waffle kit, + Raspberry Pi Camera for Waffle Pi kit), an SBC(single board computer: Raspberry PI 3 and Intel Joule 570x) and a hardware mounting kit attaching everything together and adding future sensors. Turtlebot3 was released in May 2017.+The most recent and developed version of the turtlebot is version 3. TurtleBot3 is made up of modular plates that users can customize the shape. Available in three types: small-size Burger and medium-size Waffle, Waffle Pi. TurtleBot3 consists of a base, two Dynamixel motors, a 1,800mAh battery pack, a 360 degree LIDAR, a camera (+ RealSense camera for Waffle kit, + Raspberry Pi Camera for Waffle Pi kit), and SBC (single-board computer: Raspberry PI 3 and Intel Joule 570x) and a hardware mounting kit attaching everything together and adding future sensors. Turtlebot3 was released in May 2017.
  
 {{ :en:ros:simulations:turtlebot3_burger_components.png?400 |}} {{ :en:ros:simulations:turtlebot3_burger_components.png?400 |}}
 +
 ===== Sensors ===== ===== Sensors =====
-The main sensor of the turtlebot is the 360 Laser Distance Sensor LDS-01. The LDS-01 is a 2D laser scanner capable of sensing 360 degrees that collects a set of data around the robot to use for SLAM (Simultaneous Localization and Mapping). The below fidure shows that how a the robot sees the environment from a 360 laser sensor. The blue laser rays are reflected from the objects and the distance is measured and finally a 2D point-cloud of the environment is built. +The main sensor of the turtlebot is the 360 Laser Distance Sensor LDS-01. The LDS-01 is a 2D laser scanner capable of sensing 360 degrees that collects a set of data around the robot to use for SLAM (Simultaneous Localization and Mapping). The below figure shows that how a robot sees the environment from a 360 laser sensor. The blue laser rays are reflected from the objects and the distance is measured and finallya 2D point cloud of the environment is built. 
  
 {{ :en:ros:simulations:gazebo_cartographer.png?500 |}} {{ :en:ros:simulations:gazebo_cartographer.png?500 |}}
  
-The 3D camera is one of the most versatile robot sensors. One output of a 3D camera is a 2D camera image, which means that various object recognition algorithms can be used. Many machine vision libraries are available for ROS. One of the most widely used and versatile is [[https://opencv.org/|OpenCV]]. In addition, for example, the most up-to-date artificial intelligence library [[https://pjreddie.com/darknet/yolo|You only look once (YOLO)]] is available. The same library is used by [[http://iseauto.ttu.ee/|Iseauto]] for object recognition.+The 3D camera is one of the most versatile robot sensors. One output of a 3D camera is a 2D camera image, which means that various object recognition algorithms can be used. Many machine vision libraries are available for ROS. One of the most widely used and versatile is [[https://opencv.org/|OpenCV]]. In addition, for example, the most up-to-date artificial intelligence library [[https://pjreddie.com/darknet/yolo|You only look once (YOLO)]] is available. 
  
 Objects will be identified and a box will be drawn around them, with the name of the object type identified: Objects will be identified and a box will be drawn around them, with the name of the object type identified:
Line 25: Line 26:
 ===== Turtlebot 3 Simulation ===== ===== Turtlebot 3 Simulation =====
  
-To simulate a turtle robot, everything you need to simulate a Gazebos robot is freely available on the Internet. 
  
 ==== Install Dependent ROS 1 Packages ==== ==== Install Dependent ROS 1 Packages ====
-First of all, you need to install some dependencies. These are based on Ubuntu 18.04 and ROS melodic.+First of all, you need to install some dependencies. These are based on Ubuntu 18.04 and ROS Melodic.
  
   $ sudo apt-get install ros-melodic-joy ros-melodic-teleop-twist-joy \   $ sudo apt-get install ros-melodic-joy ros-melodic-teleop-twist-joy \
Line 48: Line 48:
  
 ==== Install Simulation Package ==== ==== Install Simulation Package ====
-The TurtleBot3 Simulation Package requires //turtlebot3// and //turtlebot3_msgs// packages as prerequisite. Without these prerequisite packages, the Simulation cannot be launched.+The TurtleBot3 Simulation Package requires //turtlebot3// and //turtlebot3_msgs// packages as prerequisite. Without these prerequisite packages, the simulation cannot be launched.
  
   $ cd ~/catkin_ws/src/   $ cd ~/catkin_ws/src/
Line 55: Line 55:
      
 ==== Set TurtleBot3 Model Name ==== ==== Set TurtleBot3 Model Name ====
-Set the default TURTLEBOT3_MODEL name to your model. Enter the below command to a terminal.+Set the default //TURTLEBOT3_MODEL// name to your model. Enter the below command to a terminal.
  
 In case of TurtleBot3 Burger: In case of TurtleBot3 Burger:
Line 80: Line 80:
 {{ :en:ros:simulations:turtlebot3_house.png?600 |}} {{ :en:ros:simulations:turtlebot3_house.png?600 |}}
  
-In case you need to build your environment, you can use gazebo building editor tools (Edit > Building Editor) to create a customer shape building.+ 
 +In case you need to build your environment, you can use Gazebo building editor tools (Edit > Building Editor) to create a customer shape building.
 {{  :en:ros:simulations:gazebo3.png  |}} {{  :en:ros:simulations:gazebo3.png  |}}
  
  
-In the Gazebo Simulator, you can add simulation objects from the menu by clicking on the desired object. You'll also find tools for moving, enlarging and rotating objects in the same place.+In the Gazebo Simulator, you can add simulation objects from the menu by clicking on the desired object. You'll also find tools for moving, enlargingand rotating objects in the same place.
  
 {{ :et:ros:simulations:gazebogui.png?700 |}} {{ :et:ros:simulations:gazebogui.png?700 |}}
  
-Next we try to control the robot remotely.+ 
 +Nextwe try to control the robot remotely.
  
 ==== Operate TurtleBot3 ==== ==== Operate TurtleBot3 ====
Line 97: Line 99:
 Using the keyboard, we should now see how Turtlebot moves in the simulation. Using the keyboard, we should now see how Turtlebot moves in the simulation.
  
-===== Visualize Simulation data(RViz) =====+===== Visualize Simulation data (RViz) =====
 RViz visualizes published topics while the simulation is running. You can launch RViz in a new terminal window by entering the below command. RViz visualizes published topics while the simulation is running. You can launch RViz in a new terminal window by entering the below command.
  
Line 110: Line 112:
 **Run SLAM Node** **Run SLAM Node**
  
-Open a new terminal, and run the SLAM node. Gmapping SLAM method is used by default. We already set the robot model to burger in the //.bashrc// file.+Open a new terminal, and run the SLAM node. G mapping SLAM method is used by default. We already set the robot model to burger in the //.bashrc// file.
  
   $ roslaunch turtlebot3_slam turtlebot3_slam.launch slam_methods:=gmapping   $ roslaunch turtlebot3_slam turtlebot3_slam.launch slam_methods:=gmapping
Line 116: Line 118:
 **Run Teleoperation Node** **Run Teleoperation Node**
  
-Open a new terminal with Ctrl + Alt + T and run the teleoperation node. Move the robot and take a look to RViz, you are scanning the area by the laser sensor and creating map out of it.+Open a new terminal with Ctrl + Alt + T and run the teleoperation node. Move the robot and take a look at RViz, you are scanning the area by the laser sensor and creating map out of it.
  
   $ roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch   $ roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch
Line 139: Line 141:
  
 {{ :en:ros:simulations:map.png?400 |}} {{ :en:ros:simulations:map.png?400 |}}
-====== Clearbot ====== 
  
-[[https://clearbot.eu|Clearbot]] is an educational robot platform for advanced robotics enthusiasts. ClearBot opens up the opportunity to teach and learn complex technologies through simple, hands-on activitiesClearBot software is based on the ROS software frameworkwhich provides the most up-to-date solutions for robot control, mapping, navigation, image processing, simulation, etc.+==== Navigation Simulation ==== 
 +Just like the SLAM in the Gazebo simulator, you can select or create various environments and robot models in a virtual Navigation worldHowevera proper map has to be prepared before running the Navigation.
  
-The ClearBot robot is developed for teaching purposes in cooperation with the University of Tartu Institute of Technology.+**1Launch Simulation World**
  
-{{ :et:ros:simulations:clearbot.jpg?500 |}}+Stop all previous launch files and running the node by "Ctrl + C"In the previous SLAM section, "TurtleBot3_World.world" is used to create a map. The same Gazebo environment will be used for Navigation. So run the simulation in the same world file :
  
-===== Engines ===== +  $ roslaunch turtlebot3_gazebo turtlebot3_world.launch 
- +   
-| Voltage | 12V | +**2Run Navigation Node**
-| Max rpm | 500 | +
-| Max moment | 0.59 Nm | +
-| Transfer | 19: 1 | +
-| Encoder Resolution | 1200 cpr |+
  
-===== 3D Camera =====+  $ roslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=$HOME/map.yaml
  
-| Depth Resolution | 1280 x 720 | +**3Estimate Initial Pose**
-| Min Depth | 110mm | +
-| Max depth |  | +
-| Vertical field of vision | 85.2 ° | +
-| Horizontal field of vision | 58 ° | +
-| RGB camera resolution | 1920x1080 | +
-| RGB Camera Frame Rate | 30 fps |+
  
-===== Omnir wheels =====+Initial Pose Estimation must be performed before defining the destination for autonomous navigation as this process initializes the AMCL parameters that are critical in Navigation. TurtleBot3 has to be correctly located on the map with the LDS sensor data that neatly overlaps the displayed map.
  
-Omnidirectional wheels are wheels which are covered with rollers perpendicular to the wheel shaft, thus allowing the wheel to move in a transverse direction in addition to the normal direction of rotationOmnidirectional wheels give the robot excellent maneuverability and flexible two-dimensional movement.+3.1. Click the 2D Pose Estimate button in the RViz menu. 
 +{{ :en:ros:simulations:2d_pose_button.png?600 |}}
  
-{{ :et:ros:simulations:u6ka.gif |}} +3.2. Click on the map where the actual robot is located and drag the large green arrow toward the direction where the robot is facing.
-{{ :et:ros:simulations:triple_rotacaster_commercial_industrial_omni_wheel.jpg?500 |}}+
  
-<hidden>+{{ :en:ros:simulations:screenshot_from_2021-03-30_14-38-31.png?500 |}}
  
-===== Using Clearbot =====+You can repeat steps 1 and 2 until the LDS sensor data is overlayed on the saved map.
  
-To learn how to use Clearbot, there are in-depth internships created by the Institute of Technology at the University of Tartu:+{{ :en:ros:simulations:screenshot_from_2021-03-30_14-40-09.png?500 |}}
  
-[[https://ut-ims-robotics.github.io/robotont/html/labs/praktikum1.html|Praktikum 1 - Linux, ssh, Keyboard Control for Robot]]+NB! 2D Pose Estimate actually publishes the position and direction into the /initial pose topicSo you can publish it by the command line or a script
  
-[[https://ut-ims-robotics.github.io/robotont/html/labs/praktikum2.html|Praktikum 2 - Programming Basics: For-Cycle, Functions]]+**4Set Navigation Goal**
  
-[[https://ut-ims-robotics.github.io/robotont/html/labs/praktikum3.html|Praktikum 3 - Sensors, if-sentence, bang-bang controller]]+4.1 Click the 2D Nav Goal button in the RViz menu.
  
-[[https://ut-ims-robotics.github.io/robotont/html/labs/praktikum4.html|Praktikum 4 - AR Markers]]+{{ :en:ros:simulations:2d_nav_goal_button.png?600 |}}
  
-[[https://ut-ims-robotics.github.io/robotont/html/labs/praktikum5.html|Praktikum 5 - 2d Mapping, Automatic Navigation]]+4.2 Click on the map to set the destination of the robot and drag the green arrow toward the direction where the robot will be facing.
  
-[[https://ut-ims-robotics.github.io/robotont/html/labs/praktikum6.html|Praktikum 6 - 3D Mapping]]+{{ :en:ros:simulations:screenshot_from_2021-03-30_14-51-19.png?500 |}}
  
-[[https://ut-ims-robotics.github.io/robotont/html/labs/praktikum7.html|Praktikum 7 - Regulators]]+  *This green arrow is a marker that can specify the destination of the robot. 
 +  *The root of the arrow is the x, y coordinate of the destination, and the angle θ is determined by the orientation of the arrow. 
 +  *As soon as x, y, θ are set, TurtleBot3 will start moving to the destination immediately.
  
-[[https://ut-ims-robotics.github.io/robotont/html/labs/praktikum8.html|Praktikum 8 - Simulation]]+{{ :en:ros:simulations:screenshot_from_2021-03-30_14-51-31.png?500 |}}
  
-</hidden> 
en/ros/simulations/turtlebot.1617096560.txt.gz · Last modified: 2021/03/30 09:00 (external edit)
CC Attribution-Share Alike 4.0 International
www.chimeric.de Valid CSS Driven by DokuWiki do yourself a favour and use a real browser - get firefox!! Recent changes RSS feed Valid XHTML 1.0