Navigation 2 Logo
latest
  • Getting Started
    • Installation
    • Running the Example
    • Navigating
  • Build and Install
    • Install
    • Build
      • For Released Distributions
        • Install ROS
        • Build Nav2
      • For Main Branch Development
        • Build ROS 2 Main
        • Build Nav2 Main
    • Docker
      • Building Docker Container
      • Using DockerHub Container
    • Generate Doxygen
    • Help
      • Build Troubleshooting Guide
        • Common Nav2 Dependencies Build Failures
        • Reporting Issue
  • Navigation Concepts
    • ROS 2
      • Action Server
      • Lifecycle Nodes and Bond
    • Behavior Trees
    • Navigation Servers
      • Planner, Controller, Smoother and Recovery Servers
      • Planners
      • Controllers
      • Behaviors
      • Smoothers
      • Waypoint Following
    • State Estimation
      • Standards
      • Global Positioning: Localization and SLAM
      • Odometry
    • Environmental Representation
      • Costmaps and Layers
      • Costmap Filters
      • Other Forms
    • Nav2 Academic Overview
  • First-Time Robot Setup Guide
    • Setting Up Transformations
      • Transforms Introduction
      • Static Transform Publisher Demo
      • Transforms in Navigation2
      • Conclusion
    • Setting Up The URDF
      • URDF and the Robot State Publisher
      • Setting Up the Environment
      • Writing the URDF
      • Build and Launch
      • Visualization using RVIZ
      • Adding Physical Properties
      • Conclusion
    • Setting Up Odometry
      • Odometry Introduction
      • Setting Up Odometry on your Robot
      • Simulating an Odometry System using Gazebo
        • Setup and Prerequisites
        • Adding Gazebo Plugins to a URDF
        • Launch and Build Files
        • Build, Run and Verification
      • Robot Localization Demo
        • Configuring Robot Localization
        • Launch and Build Files
        • Build, Run and Verification
      • Conclusion
    • Setting Up Sensors
      • Sensor Introduction
        • Common Sensor Messages
      • Simulating Sensors using Gazebo
        • Adding Gazebo Plugins to a URDF
        • Launch and Build Files
        • Build, Run and Verification
      • Mapping and Localization
      • Costmap 2D
        • Configuring nav2_costmap_2d
        • Build, Run and Verification
      • Conclusion
    • Setting Up the Robot’s Footprint
      • Footprint Introduction
      • Configuring the Robot’s Footprint
      • Build, Run and Verification
      • Visualizing Footprint in RViz
      • Conclusion
    • Setting Up Navigation Plugins
      • Planner and Controller Servers
      • Selecting the Algorithm Plugins
        • Planner Server
        • Controller Server
      • Conclusion
  • General Tutorials
    • Navigating with a Physical Turtlebot 3
      • Overview
      • Requirements
      • Tutorial Steps
        • 0- Setup Your Enviroment Variables
        • 1- Launch Turtlebot 3
        • 2- Launch Nav2
        • 3- Launch RVIZ
        • 4- Initialize the Location of Turtlebot 3
        • 5- Send a Goal Pose
    • (SLAM) Navigating While Mapping
      • Overview
      • Requirements
      • Tutorial Steps
        • 0- Launch Robot Interfaces
        • 1- Launch Navigation2
        • 2- Launch SLAM
        • 3- Working with SLAM
        • 4- Getting Started Simplification
    • (STVL) Using an External Costmap Plugin
      • Overview
      • Costmap2D and STVL
      • Tutorial Steps
        • 0- Setup
        • 1- Install STVL
        • 1- Modify Navigation2 Parameter
        • 2- Launch Navigation2
        • 3- RVIZ
    • Groot - Interacting with Behavior Trees
      • Overview
      • Visualize Behavior Trees
      • Edit Behavior Trees
      • Adding A Custom Node
    • Camera Calibration
      • Overview
      • Requirements
      • Tutorial Steps
    • Get Backtrace in ROS 2 / Nav2
      • Overview
      • Preliminaries
      • From a Node
      • From a Launch File
      • From Large Project
      • From Nav2 Bringup
      • Automatic backtrace on crash
    • Profiling in ROS 2 / Nav2
      • Overview
      • Preliminaries
      • Profile from a Node
      • Profile from a Launch File
      • From Nav2 Bringup
      • Interpreting Results
    • Dynamic Object Following
      • Overview
      • Tutorial Steps
        • 0- Create the Behavior Tree
        • 1- Setup Rviz clicked point
        • 2- Run Dynamic Object Following in Nav2 Simulation
    • Navigating with Keepout Zones
      • Overview
      • Requirements
      • Tutorial Steps
        • 1. Prepare filter mask
        • 2. Configure Costmap Filter Info Publisher Server
        • 3. Enable Keepout Filter
        • 4. Run Nav2 stack
    • Navigating with Speed Limits
      • Overview
      • Requirements
      • Tutorial Steps
        • 1. Prepare filter mask
        • 2. Configure Costmap Filter Info Publisher Server
        • 3. Enable Speed Filter
        • 4. Run Nav2 stack
    • Using Rotation Shim Controller
      • Overview
      • What is the Rotation Shim Controller?
      • Configuring Rotation Shim Controller
      • Configuring Primary Controller
      • Demo Execution
    • Adding a Smoother to a BT
      • Overview
      • Requirements
      • Tutorial Steps
        • 0- Familiarization with the Smoother BT Node
        • 1- Specifying a Smoother Plugin
        • 2- Modifying your BT XML
    • Using Collision Monitor
      • Overview
      • Requirements
      • Configuring Collision Monitor
      • Preparing Nav2 stack
      • Demo Execution
    • Adding a New Nav2 Task Server
      • Lifecycle Nodes
      • Composition
      • Error codes
      • Conclusion
  • Plugin Tutorials
    • Writing a New Costmap2D Plugin
      • Overview
      • Requirements
      • Tutorial Steps
        • 1- Write a new Costmap2D plugin
        • 2- Export and make GradientLayer plugin
        • 3- Enable the plugin in Costmap2D
        • 4- Run GradientLayer plugin
    • Writing a New Planner Plugin
      • Overview
      • Requirements
      • Tutorial Steps
        • 1- Creating a new Planner Plugin
        • 2- Exporting the planner plugin
        • 3- Pass the plugin name through params file
        • 4- Run StraightLine plugin
    • Writing a New Controller Plugin
      • Overview
      • Requirements
      • Tutorial Steps
        • 1- Create a new Controller Plugin
        • 2- Exporting the controller plugin
        • 3- Pass the plugin name through the params file
        • 4- Run Pure Pursuit Controller plugin
    • Writing a New Behavior Tree Plugin
      • Overview
      • Requirements
      • Tutorial Steps
        • 1- Creating a new BT Plugin
        • 2- Exporting the planner plugin
        • 3- Add plugin library name to config
        • 4- Run Your Custom plugin
    • Writing a New Behavior Plugin
      • Overview
      • Requirements
      • Tutorial Steps
        • 1- Creating a new Behavior Plugin
        • 2- Exporting the Behavior Plugin
        • 3- Pass the plugin name through params file
        • 4- Run Behavior Plugin
    • Writing a New Navigator Plugin
      • Overview
      • Requirements
      • Tutorial Steps
        • 1- Create a new Navigator Plugin
        • 2- Exporting the navigator plugin
        • 3- Pass the plugin name through the params file
        • 4- Run plugin
  • Configuration Guide
    • Behavior-Tree Navigator
      • Parameters
      • Example
    • Behavior Tree XML Nodes
      • Action Plugins
        • Wait
        • Spin
        • BackUp
        • DriveOnHeading
        • AssistedTeleop
        • ComputePathToPose
        • FollowPath
        • NavigateToPose
        • ClearEntireCostmap
        • ClearCostmapExceptRegion
        • ClearCostmapAroundRobot
        • ReinitializeGlobalLocalization
        • TruncatePath
        • TruncatePathLocal
        • PlannerSelector
        • ControllerSelector
        • SmootherSelector
        • GoalCheckerSelector
        • NavigateThroughPoses
        • ComputePathThroughPoses
        • RemovePassedGoals
        • CancelControl
        • CancelBackUp
        • CancelSpin
        • CancelWait
        • CancelDriveOnHeading
        • CancelAssistedTeleop
        • SmoothPath
      • Condition Plugins
        • GoalReached
        • TransformAvailable
        • DistanceTraveled
        • GoalUpdated
        • GloballyUpdatedGoal
        • InitialPoseReceived
        • IsStuck
        • TimeExpired
        • IsBatteryLow
        • IsPathValid
        • PathExpiringTimer
        • AreErrorCodesPresent
        • WouldAControllerRecoveryHelp
        • WouldAPlannerRecoveryHelp
        • WouldASmootherRecoveryHelp
      • Control Plugins
        • PipelineSequence
        • RoundRobin
        • RecoveryNode
      • Decorator Plugins
        • RateController
        • DistanceController
        • SpeedController
        • GoalUpdater
        • PathLongerOnApproach
        • SingleTrigger
      • Example
    • Costmap 2D
      • Costmap2D ROS Parameters
      • Default Plugins
      • Plugin Parameters
        • Static Layer Parameters
        • Inflation Layer Parameters
        • Obstacle Layer Parameters
        • Voxel Layer Parameters
        • Range Sensor Parameters
      • Costmap Filters Parameters
        • Keepout Filter Parameters
        • Speed Filter Parameters
        • Binary Filter Parameters
      • Example
    • Lifecycle Manager
      • Parameters
      • Example
    • Planner Server
      • Parameters
      • Default Plugins
      • Example
    • NavFn Planner
      • Parameters
      • Example
    • Smac Planner
      • Provided Plugins
        • Smac 2D Planner
        • Smac Hybrid-A* Planner
        • Smac State Lattice Planner
      • Description
    • Theta Star Planner
      • Parameters
      • Example
    • Controller Server
      • Parameters
      • Provided Plugins
        • SimpleProgressChecker
        • SimpleGoalChecker
        • StoppedGoalChecker
      • Default Plugins
      • Example
    • DWB Controller
      • Controller
        • DWB Controller
        • XYTheta Iterator
        • Kinematic Parameters
        • Publisher
      • Plugins
        • LimitedAccelGenerator
        • StandardTrajectoryGenerator
      • Trajectory Critics
        • BaseObstacleCritic
        • GoalAlignCritic
        • GoalDistCritic
        • ObstacleFootprintCritic
        • OscillationCritic
        • PathAlignCritic
        • PathDistCritic
        • PreferForwardCritic
        • RotateToGoalCritic
        • TwirlingCritic
      • Example
    • Regulated Pure Pursuit
      • Regulated Pure Pursuit Parameters
      • Example
    • Model Predictive Path Integral Controller
      • MPPI Parameters
        • Trajectory Visualization
        • Path Handler
        • Ackermann Motion Model
        • Constraint Critic
        • Goal Angle Critic
        • Goal Critic
        • Obstacles Critic
        • Path Align Critic
        • Path Angle Critic
        • Path Follow Critic
        • Prefer Forward Critic
        • Twirling Critic
      • Example
      • Notes to Users
        • General Words of Wisdom
        • Prediction Horizon, Costmap Sizing, and Offsets
        • Obstacle, Inflation Layer, and Path Following
    • Rotation Shim Controller
      • Rotation Shim Controller Parameters
      • Example
    • Map Server / Saver
      • Map Saver Parameters
      • Map Server Parameters
      • Costmap Filter Info Server Parameters
      • Example
    • AMCL
      • Parameters
      • Example
    • Behavior Server
      • Behavior Server Parameters
      • Default Plugins
      • Spin Behavior Parameters
      • BackUp Behavior Parameters
      • DriveOnHeading Behavior Parameters
      • AssistedTeleop Behavior Parameters
      • Example
    • Smoother Server
      • Smoother Server Parameters
      • Example
    • Simple Smoother
      • Simple Smoother Parameters
      • Example
    • Savitzky-Golay Smoother
      • Savitzky-Golay Smoother Parameters
      • Example
    • Constrained smoother
      • Smoother Server Parameters
      • Example
    • Velocity Smoother
      • Velocity Smoother Parameters
      • Example
    • Collision Monitor
      • Features
      • Parameters
        • Polygons parameters
        • Observation sources parameters
      • Example
    • Waypoint Follower
      • Parameters
      • Provided Plugins
        • WaitAtWaypoint
        • PhotoAtWaypoint
        • InputAtWaypoint
      • Default Plugin
      • Example
  • Tuning Guide
    • Inflation Potential Fields
    • Robot Footprint vs Radius
    • Rotate in Place Behavior
    • Planner Plugin Selection
    • Controller Plugin Selection
    • Caching Obstacle Heuristic in Smac Planners
    • Nav2 Launch Options
    • Other Pages We’d Love To Offer
  • Nav2 Behavior Trees
    • Introduction To Nav2 Specific Nodes
      • Action Nodes
      • Condition Nodes
      • Decorator Nodes
      • Control: PipelineSequence
      • Control: Recovery
      • Control: RoundRobin
    • Detailed Behavior Tree Walkthrough
      • Overview
      • Prerequisites
      • Navigate To Pose With Replanning and Recovery
      • Navigation Subtree
      • Recovery Subtree
    • Navigate To Pose
    • Navigate Through Poses
    • Navigate To Pose and Pause Near Goal-Obstacle
    • Navigate To Pose With Consistent Replanning And If Path Becomes Invalid
    • Follow Dynamic Point
    • Odometry Calibration
  • Navigation Plugins
    • Behavior-Tree Navigators
    • Costmap Layers
    • Costmap Filters
    • Controllers
    • Planners
    • Smoothers
    • Behaviors
    • Waypoint Task Executors
    • Goal Checkers
    • Progress Checkers
    • Behavior Tree Nodes
  • Migration Guides
    • Dashing to Eloquent
      • New Packages
      • New Plugins
      • Navigation2 Architectural Changes
    • Eloquent to Foxy
      • General
      • Server Updates
      • New Plugins
      • Map Server Re-Work
      • New Particle Filter Messages
      • Selection of Behavior Tree in each navigation action
      • FollowPoint Capability
      • New Costmap Layer
    • Foxy to Galactic
      • NavigateToPose Action Feedback updates
      • NavigateToPose BT-node Interface Changes
      • NavigateThroughPoses and ComputePathThroughPoses Actions Added
      • ComputePathToPose BT-node Interface Changes
      • ComputePathToPose Action Interface Changes
      • BackUp BT-node Interface Changes
      • BackUp Recovery Interface Changes
      • Nav2 Controllers and Goal Checker Plugin Interface Changes
      • FollowPath goal_checker_id attribute
      • Groot Support
      • New Plugins
      • Costmap Filters
      • SmacPlanner
      • ThetaStarPlanner
      • RegulatedPurePursuitController
      • Costmap2D current_ Usage
      • Standard time units in parameters
      • Ray Tracing Parameters
      • Obstacle Marking Parameters
      • Recovery Action Changes
      • Default Behavior Tree Changes
      • NavFn Planner Parameters
      • New ClearCostmapExceptRegion and ClearCostmapAroundRobot BT-nodes
      • New Behavior Tree Nodes
      • sensor_msgs/PointCloud to sensor_msgs/PointCloud2 Change
      • ControllerServer New Parameter failure_tolerance
      • Removed BT XML Launch Configurations
      • Nav2 RViz Panel Action Feedback Information
    • Galactic to Humble
      • Major improvements to Smac Planners
      • Simple (Python) Commander
      • Reduce Nodes and Executors
      • API Change for nav2_core
      • Extending the BtServiceNode to process Service-Results
      • Including new Rotation Shim Controller Plugin
      • Spawning the robot in Gazebo
      • Recovery Behavior Timeout
      • New parameter use_final_approach_orientation for the 3 2D planners
      • SmacPlanner2D and Theta*: fix goal orientation being ignored
      • SmacPlanner2D, NavFn and Theta*: fix small path corner cases
      • Change and fix behavior of dynamic parameter change detection
      • Dynamic Parameters
      • BT Action Nodes Exception Changes
      • BT Navigator Groot Multiple Navigators
      • Removed Kinematic Limiting in RPP
      • Added Smoother Task Server
      • Removed Use Approach Velocity Scaling Param in RPP
      • Refactored AMCL motion models as plugins
      • Dropping Support for Live Groot Monitoring of Nav2
      • Replanning Only if Path is Invalid
      • Fix CostmapLayer clearArea invert param logic
      • Dynamic Composition
      • BT Cancel Node
      • BT PathLongerOnApproach Node
      • BT TruncatePathLocal Node
      • Constrained Smoother
      • Replanning at a Constant Rate and if the Path is Invalid
      • Euclidean Distance 2D
      • Recovery To Behavior
      • Respawn Support in Launch and Lifecycle Manager
      • New Nav2 Velocity Smoother
      • Goal Checker API Changed
      • Added Assisted Teleop
    • Humble to Iron
      • New Behavior-Tree Navigator Plugins
      • Added Collision Monitor
      • Removed use_sim_time from yaml
      • Run-time Speed up of Smac Planner
      • Recursive Refinement of Smac and Simple Smoothers
      • Simple Commander Python API
      • Smac Planner Start Pose Included in Path
      • Parameterizable Collision Checking in RPP
      • Expanded Planner Benchmark Tests
      • Smac Planner Path Tolerances
      • costmap_2d_node default constructor
      • Feedback for Navigation Failures
      • Costmap Filters
      • Savitzky-Golay Smoother
      • Changes to Map yaml file path for map_server node in Launch
      • SmootherSelector BT Node
      • Publish Costmap Layers
      • Give Behavior Server Access to Both Costmaps
      • New Model Predictive Path Integral Controller
      • Behavior Tree Uses Error Codes
      • Load, Save and Loop Waypoints from the Nav2 Panel in RViz
      • DWB Forward vs Reverse Pruning
      • More stable regulation on curves for long lookahead distances
  • Simple Commander API
    • Overview
    • Commander API
    • Costmap API
    • Footprint Collision Checker API
    • Examples and Demos
  • Roadmaps
    • Iron Roadmap
    • Humble Roadmap
  • Getting Involved
    • Getting Involved
    • Process
    • Licensing
    • Developer Certification of Origin (DCO)
  • About and Contact
    • Related Projects
    • ROS to ROS 2 Navigation
    • About
    • Contact
  • Robots Using
Navigation 2
Edit
  • General Tutorials
  • Navigating with a Physical Turtlebot 3

Navigating with a Physical Turtlebot 3¶

  • Overview

  • Requirements

  • Tutorial Steps

Overview¶

This tutorial shows how to control and navigate Turtlebot 3 using the ROS 2 Nav2 on a physical Turtlebot 3 robot. Before completing this tutorials, completing Getting Started is highly recommended especially if you are new to ROS and Nav2.

This tutorial may take about 1 hour to complete. It depends on your experience with ROS, robots, and what computer system you have.

Requirements¶

You must install Nav2, Turtlebot3. If you don’t have them installed, please follow Getting Started.

Tutorial Steps¶

0- Setup Your Enviroment Variables¶

Run the following commands first whenever you open a new terminal during this tutorial.

  • source /opt/ros/<ros2-distro>/setup.bash

  • export TURTLEBOT3_MODEL=waffle

1- Launch Turtlebot 3¶

You will need to launch your robot’s interface,

ros2 launch turtlebot3_bringup robot.launch.py  use_sim_time:=False

2- Launch Nav2¶

You need to have a map of the environment where you want to Navigate Turtlebot 3, or create one live with SLAM.

In case you are interested, there is a use case tutorial which shows how to use Nav2 with SLAM. Nav2 with SLAM

Required files:

  • your-map.map

  • your-map.yaml

<your_map>.yaml is the configuration file for the map we want to provide Nav2. In this case, it has the map resolution value, threshold values for obstacles and free spaces, and a map file location. You need to make sure these values are correct. More information about the map.yaml can be found here.

Launch Nav2. If you set autostart:=False, you need to click on the start button in RViz to initialize the nodes. Make sure use_sim time is set to False, because we want to use the system time instead of the time simulation time from Gazebo.

ros2 launch nav2_bringup bringup_launch.py use_sim_time:=False autostart:=False map:=/path/to/your-map.yaml

Note: Don’t forget to change /path/to/your-map.yaml to the actual path to the your-map.yaml file.

3- Launch RVIZ¶

Launch RVIZ with a pre-defined configuration file.

ros2 run rviz2 rviz2 -d $(ros2 pkg prefix nav2_bringup)/share/nav2_bringup/rviz/nav2_default_view.rviz

Now, you should see a shadow of Turtlebot 3 robot model in the center of the plot in Rviz. Click on the Start button (Bottom Left) if you set the auto_start parameter to false. Then, the map should appear in RViz.

../../_images/rviz_after_launch_view.png ../../_images/rviz_slam_map_view.png

4- Initialize the Location of Turtlebot 3¶

First, find where the robot is on the map. Check where your robot is in the room.

Set the pose of the robot in RViz. Click on the 2D Pose Estimate button and point the location of the robot on the map. The direction of the green arrow is the orientation of Turtlebot.

Set initial pose in RViz

Now, the 3D model of Turtlebot should move to that location. A small error in the estimated location is tolerable.

5- Send a Goal Pose¶

Pick a target location for Turtlebot on the map. You can send Turtlebot 3 a goal position and a goal orientation by using the Nav2 Goal or the GoalTool buttons.

Note: Nav2 Goal button uses a ROS 2 Action to send the goal and the GoalTool publishes the goal to a topic.

Send goal pose in RViz

Once you define the target pose, Nav2 will find a global path and start navigating the robot on the map.

Robot navigating in RViz

Now, you can see that Turtlebot 3 moves towards the goal position in the room. See the video below.


© Copyright 2020.