diff --git a/README.md b/README.md index 7b02d72d176..b09affa970a 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -# Navigation 2 +# Nav2 [![Build Status](https://img.shields.io/docker/pulls/rosplanning/navigation2.svg?maxAge=2592000)](https://hub.docker.com/r/rosplanning/navigation2) [![Build Status](https://img.shields.io/docker/cloud/build/rosplanning/navigation2.svg?label=docker%20build)](https://hub.docker.com/r/rosplanning/navigation2) [![codecov](https://codecov.io/gh/ros-planning/navigation2/branch/main/graph/badge.svg)](https://codecov.io/gh/ros-planning/navigation2)

diff --git a/doc/use_cases/README.md b/doc/use_cases/README.md index 14ea423c0e9..47d6ee56885 100644 --- a/doc/use_cases/README.md +++ b/doc/use_cases/README.md @@ -1,7 +1,7 @@ # Target Use Cases -The Navigation2 system is targeting the following use cases: +The Nav2 system is targeting the following use cases: [2D Indoor Navigation](indoor_navigation_use_case.md) - example: Warehouse / Logistics robot diff --git a/nav2_behavior_tree/groot_instructions.md b/nav2_behavior_tree/groot_instructions.md index b1189a6ba6b..7ca0ac70ada 100644 --- a/nav2_behavior_tree/groot_instructions.md +++ b/nav2_behavior_tree/groot_instructions.md @@ -7,6 +7,6 @@ To visualize the behavior trees using Groot: 1. Open Groot in editor mode 2. Select the `Load palette from file` option (import button) near the top left corner. -3. Open the file `/path/to/navigation2/nav2_behavior_tree/nav2_tree_nodes.xml` to import all the behavior tree nodes used for navigation. +3. Open the file `/path/to/nav2/nav2_behavior_tree/nav2_tree_nodes.xml` to import all the behavior tree nodes used for navigation. 4. Select `Load tree` option near the top left corner 5. Browse the tree you want to visualize the select ok. diff --git a/nav2_bringup/bringup/README.md b/nav2_bringup/bringup/README.md index a4a1b9a6f66..da9e64eb411 100644 --- a/nav2_bringup/bringup/README.md +++ b/nav2_bringup/bringup/README.md @@ -1,20 +1,20 @@ # nav2_bringup -The `nav2_bringup` package is an example bringup system for Navigation2 applications. +The `nav2_bringup` package is an example bringup system for Nav2 applications. ### Pre-requisites: * [Install ROS 2](https://index.ros.org/doc/ros2/Installation/Dashing/) -* Install Navigation2 +* Install Nav2 ```sudo apt install ros--navigation2``` -* Install Navigation2 Bringup +* Install Nav2 Bringup ```sudo apt install ros--nav2-bringup``` * Install your robot specific package (ex:[Turtlebot 3](http://emanual.robotis.com/docs/en/platform/turtlebot3/ros2/)) -## Launch Navigation2 in *Simulation* with Gazebo +## Launch Nav2 in *Simulation* with Gazebo ### Pre-requisites: * [Install Gazebo](http://gazebosim.org/tutorials?tut=install_ubuntu&cat=install) @@ -43,7 +43,7 @@ export TURTLEBOT3_MODEL=waffle ros2 launch turtlebot3_bringup turtlebot3_state_publisher.launch.py use_sim_time:=True ``` -### Terminal 3: Launch Navigation2 +### Terminal 3: Launch Nav2 ```bash source /opt/ros/dashing/setup.bash @@ -51,7 +51,7 @@ ros2 launch nav2_bringup bringup_launch.py use_sim_time:=True autostart:=True \ map:= ``` -### Terminal 4: Run RViz with Navigation2 config file +### Terminal 4: Run RViz with Nav2 config file ```bash source /opt/ros/dashing/setup.bash @@ -62,7 +62,7 @@ In RViz: * You should see the map * Localize the robot using “2D Pose Estimate” button. * Make sure all transforms from odom are present. (odom->base_link->base_scan) -* Send the robot a goal using “Navigation2 Goal” button. +* Send the robot a goal using "Nav2 Goal” button. Note: this uses a ROS2 Action to send the goal, and a pop-up window will appear on your screen with a 'cancel' button if you wish to cancel To view the robot model in RViz: @@ -70,7 +70,7 @@ To view the robot model in RViz: ### Advanced: single-terminal launch -A convenience file is provided to launch Gazebo, RVIZ and Navigation2 using a single command: +A convenience file is provided to launch Gazebo, RVIZ and Nav2 using a single command: ```bash ros2 launch nav2_bringup tb3_simulation_launch.py @@ -102,7 +102,7 @@ ros2 launch nav2_bringup multi_tb3_simulation_launch.py ``` -## Launch Navigation2 on a *Robot* +## Launch Nav2 on a *Robot* ### Pre-requisites: * Run SLAM with Navigation 2 or tele-op to drive the robot and generate a map of an area for testing first. The directions below assume this has already been done or there is already a map of the area. @@ -111,12 +111,12 @@ ros2 launch nav2_bringup multi_tb3_simulation_launch.py - [Navigation 2 with SLAM](https://github.com/ros-planning/navigation2/blob/main/doc/use_cases/navigation_with_slam.md) -* _Please note that currently, nav2_bringup works if you provide a map file. However, providing a map is not required to use Navigation2. Navigation2 can be configured to use the costmaps to navigate in an area without using a map file_ +* _Please note that currently, nav2_bringup works if you provide a map file. However, providing a map is not required to use Nav2. Nav2 can be configured to use the costmaps to navigate in an area without using a map file_ * Publish all the transforms from your robot from base_link to base_scan -### Terminal 1 : Launch Navigation2 using your map.yaml +### Terminal 1 : Launch Nav2 using your map.yaml ```bash source /opt/ros/dashing/setup.bash diff --git a/nav2_bringup/bringup/package.xml b/nav2_bringup/bringup/package.xml index aa4fa05bb7d..b1eb97a0d35 100644 --- a/nav2_bringup/bringup/package.xml +++ b/nav2_bringup/bringup/package.xml @@ -3,7 +3,7 @@ nav2_bringup 0.4.3 - Bringup scripts and configurations for the navigation2 stack + Bringup scripts and configurations for the Nav2 stack Michael Jeronimo Steve Macenski Carlos Orduno diff --git a/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py b/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py index 05cc3c6dbc2..bd6aa2ab219 100644 --- a/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py +++ b/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py @@ -25,7 +25,7 @@ def main(): # Get input arguments from user - parser = argparse.ArgumentParser(description='Spawn Robot into Gazebo with navigation2') + parser = argparse.ArgumentParser(description='Spawn Robot into Gazebo with Nav2') parser.add_argument('-n', '--robot_name', type=str, default='robot', help='Name of the robot to spawn') parser.add_argument('-ns', '--robot_namespace', type=str, default='robot', diff --git a/nav2_bringup/nav2_gazebo_spawner/package.xml b/nav2_bringup/nav2_gazebo_spawner/package.xml index 58ca2100273..84103d12134 100644 --- a/nav2_bringup/nav2_gazebo_spawner/package.xml +++ b/nav2_bringup/nav2_gazebo_spawner/package.xml @@ -3,7 +3,7 @@ nav2_gazebo_spawner 0.4.3 - Package for spawning a robot model into Gazebo for navigation2 + Package for spawning a robot model into Gazebo for Nav2 lkumarbe lkumarbe Apache-2.0 diff --git a/nav2_bt_navigator/README.md b/nav2_bt_navigator/README.md index f0864df97ad..26eda13d33c 100644 --- a/nav2_bt_navigator/README.md +++ b/nav2_bt_navigator/README.md @@ -20,7 +20,7 @@ Using the XML filename as a parameter makes it easy to change or extend the logi ## Behavior Tree nodes -A Behavior Tree consists of control flow nodes, such as fallback, sequence, parallel, and decorator, as well as two execution nodes: condition and action nodes. Execution nodes are the leaf nodes of the tree. When a leaf node is ticked, the node does some work and it returns either SUCCESS, FAILURE or RUNNING. The current Navigation2 software implements a few custom nodes, including Conditions and Actions. The user can also define and register additional node types that can then be used in BTs and the corresponding XML descriptions. +A Behavior Tree consists of control flow nodes, such as fallback, sequence, parallel, and decorator, as well as two execution nodes: condition and action nodes. Execution nodes are the leaf nodes of the tree. When a leaf node is ticked, the node does some work and it returns either SUCCESS, FAILURE or RUNNING. The current Nav2 software implements a few custom nodes, including Conditions and Actions. The user can also define and register additional node types that can then be used in BTs and the corresponding XML descriptions. ## Navigation Behavior Trees diff --git a/nav2_core/package.xml b/nav2_core/package.xml index 91241953ae4..e37c81853fd 100644 --- a/nav2_core/package.xml +++ b/nav2_core/package.xml @@ -3,7 +3,7 @@ nav2_core 0.4.3 - A set of headers for plugins core to the navigation2 stack + A set of headers for plugins core to the Nav2 stack Steve Macenski Carl Delsey Apache-2.0 diff --git a/nav2_costmap_2d/README.md b/nav2_costmap_2d/README.md index dc937f0435f..238eecce2d0 100644 --- a/nav2_costmap_2d/README.md +++ b/nav2_costmap_2d/README.md @@ -93,7 +93,7 @@ In order to add multiple sources to the global costmap, follow the same procedur ### Overview -Costmap Filters - is a costmap layer-based instrument which provides an ability to apply to map spatial-dependent raster features named as filter-masks. These features are used in plugin algorithms when filling costmaps in order to allow robots to change their trajectory, behavior or speed when a robot enters/leaves an area marked in a filter masks. Examples of costmap filters include keep-out/safety zones where robots will never enter, speed restriction areas, preferred lanes for robots moving in industries and warehouses. More information about design, architecture of the feature and how it works could be found on navigation2 web-site: https://navigation.ros.org. +Costmap Filters - is a costmap layer-based instrument which provides an ability to apply to map spatial-dependent raster features named as filter-masks. These features are used in plugin algorithms when filling costmaps in order to allow robots to change their trajectory, behavior or speed when a robot enters/leaves an area marked in a filter masks. Examples of costmap filters include keep-out/safety zones where robots will never enter, speed restriction areas, preferred lanes for robots moving in industries and warehouses. More information about design, architecture of the feature and how it works could be found on Nav2 website: https://navigation.ros.org. ## Future Plans - Conceptually, the costmap_2d model acts as a world model of what is known from the map, sensor, robot pose, etc. We'd like diff --git a/nav2_lifecycle_manager/README.md b/nav2_lifecycle_manager/README.md index d2112266b52..83b4a61c1b5 100644 --- a/nav2_lifecycle_manager/README.md +++ b/nav2_lifecycle_manager/README.md @@ -1,9 +1,9 @@ ### Background on lifecycle enabled nodes -Using ROS2’s managed/lifecycle nodes feature allows the system startup to ensure that all required nodes have been instantiated correctly before they begin their execution. Using lifecycle nodes also allows nodes to be restarted or replaced on-line. More details about managed nodes can be found on [ROS2 Design website](https://design.ros2.org/articles/node_lifecycle.html). Several nodes in the navigation2 stack, such as map_server, planner_server, and controller_server, are lifecycle enabled. These nodes provide the required overrides of the lifecycle functions: ```on_configure()```, ```on_activate()```, ```on_deactivate()```, ```on_cleanup()```, ```on_shutdown()```, and ```on_error()```. +Using ROS2’s managed/lifecycle nodes feature allows the system startup to ensure that all required nodes have been instantiated correctly before they begin their execution. Using lifecycle nodes also allows nodes to be restarted or replaced on-line. More details about managed nodes can be found on [ROS2 Design website](https://design.ros2.org/articles/node_lifecycle.html). Several nodes in Nav2, such as map_server, planner_server, and controller_server, are lifecycle enabled. These nodes provide the required overrides of the lifecycle functions: ```on_configure()```, ```on_activate()```, ```on_deactivate()```, ```on_cleanup()```, ```on_shutdown()```, and ```on_error()```. ### nav2_lifecycle_manager -Navigation2’s lifecycle manager is used to change the states of the lifecycle nodes in order to achieve a controlled _startup_, _shutdown_, _reset_, _pause_, or _resume_ of the navigation stack. The lifecycle manager presents a ```lifecycle_manager/manage_nodes``` service, from which clients can invoke the startup, shutdown, reset, pause, or resume functions. Based on this service request, the lifecycle manager calls the necessary lifecycle services in the lifecycle managed nodes. Currently, the RVIZ panel uses this ```lifecycle_manager/manage_nodes``` service when user presses the buttons on the RVIZ panel (e.g.,startup, reset, shutdown, etc.). +Nav2's lifecycle manager is used to change the states of the lifecycle nodes in order to achieve a controlled _startup_, _shutdown_, _reset_, _pause_, or _resume_ of the navigation stack. The lifecycle manager presents a ```lifecycle_manager/manage_nodes``` service, from which clients can invoke the startup, shutdown, reset, pause, or resume functions. Based on this service request, the lifecycle manager calls the necessary lifecycle services in the lifecycle managed nodes. Currently, the RVIZ panel uses this ```lifecycle_manager/manage_nodes``` service when user presses the buttons on the RVIZ panel (e.g.,startup, reset, shutdown, etc.). In order to start the navigation stack and be able to navigate, the necessary nodes must be configured and activated. Thus, for example when _startup_ is requested from the lifecycle manager's manage_nodes service, the lifecycle managers calls _configure()_ and _activate()_ on the lifecycle enabled nodes in the node list. diff --git a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp index dc58026f2dc..96e3f5296b6 100644 --- a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp +++ b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp @@ -36,7 +36,7 @@ using nav2_msgs::srv::ManageLifecycleNodes; /** * @class nav2_lifecycle_manager::LifecycleManager * @brief Implements service interface to transition the lifecycle nodes of - * Navigation2 stack. It receives transition request and then uses lifecycle + * Nav2 stack. It receives transition request and then uses lifecycle * interface to change lifecycle node's state. */ class LifecycleManager : public rclcpp::Node diff --git a/nav2_map_server/README.md b/nav2_map_server/README.md index 8a81a2ddc8f..a5f87748e1c 100644 --- a/nav2_map_server/README.md +++ b/nav2_map_server/README.md @@ -1,6 +1,6 @@ # Map Server -The `Map Server` provides maps to the rest of the Navigation2 system using both topic and +The `Map Server` provides maps to the rest of the Nav2 system using both topic and service interfaces. ## Changes from ROS1 Navigation Map Server @@ -62,7 +62,7 @@ occupied_thresh: 0.65 free_thresh: 0.196 ``` -The Navigation2 software retains the map YAML file format from Nav1, but uses the ROS2 parameter +The Nav2 software retains the map YAML file format from Nav1, but uses the ROS2 parameter mechanism to get the name of the YAML file to use. This effectively introduces a level of indirection to get the map yaml filename. For example, for a node named 'map_server', the parameter file would look like this: diff --git a/nav2_msgs/README.md b/nav2_msgs/README.md index 0ca22a23401..b71a9c899f9 100644 --- a/nav2_msgs/README.md +++ b/nav2_msgs/README.md @@ -1,5 +1,5 @@ # nav2_msgs -The `nav2_msgs` package is a set of messages, services, and actions for the `navigation2` stack. The `navigation2` stack still makes use of `nav_msgs` from ROS (1) Navigation. +The `nav2_msgs` package is a set of messages, services, and actions for the `Nav2` system. `Nav2` still makes use of `nav_msgs` from ROS (1) Navigation. See the ROS 1 to ROS 2 [Migration Guide](https://index.ros.org/doc/ros2/Migration-Guide/#messages-and-services) for details about use of the new message and service types. diff --git a/nav2_msgs/package.xml b/nav2_msgs/package.xml index 00265980c7d..c24761cd1aa 100644 --- a/nav2_msgs/package.xml +++ b/nav2_msgs/package.xml @@ -3,7 +3,7 @@ nav2_msgs 0.4.3 - Messages and service files for the navigation2 stack + Messages and service files for the Nav2 stack Michael Jeronimo Steve Macenski Carlos Orduno diff --git a/nav2_rviz_plugins/plugins_description.xml b/nav2_rviz_plugins/plugins_description.xml index 90bcf66d01a..197a9a750d7 100644 --- a/nav2_rviz_plugins/plugins_description.xml +++ b/nav2_rviz_plugins/plugins_description.xml @@ -9,7 +9,7 @@ - The Navigation2 rviz panel. + The Nav2 rviz panel. -smac-planner Many users and default navigation configuration files I find are really missing the point of the inflation layer. While it's true that you can simply inflate a small radius around the walls, the _true_ value of the inflation layer is creating a consistent potential field around the entire map. -Some of the most popular tuning guides for Navigation / Navigation2 even [call this out specifically](https://arxiv.org/pdf/1706.09068.pdf) that there's substantial benefit to creating a gentle potential field across the width of the map - after inscribed costs are applied - yet very few users do this. +Some of the most popular tuning guides for Navigation / Nav2 even [call this out specifically](https://arxiv.org/pdf/1706.09068.pdf) that there's substantial benefit to creating a gentle potential field across the width of the map - after inscribed costs are applied - yet very few users do this. This habit actually results in paths produced by NavFn, Global Planner, and now SmacPlanner to be very suboptimal. They really want to look for a smooth potential field rather than wide open 0-cost spaces in order to stay in the middle of spaces and deal with close-by moving obstacles better. diff --git a/nav2_system_tests/scripts/ctest_loop.bash b/nav2_system_tests/scripts/ctest_loop.bash index 3a3fc36d496..29f0e278289 100755 --- a/nav2_system_tests/scripts/ctest_loop.bash +++ b/nav2_system_tests/scripts/ctest_loop.bash @@ -1,7 +1,7 @@ #!/bin/bash # -# Simple bash script to loop over the navigation2 "bt_navigator" system test +# Simple bash script to loop over the Nav2 "bt_navigator" system test # # options: # -c <#> - number of times to loop diff --git a/nav2_system_tests/src/system/README.md b/nav2_system_tests/src/system/README.md index d78e9284650..7160a7bdf46 100644 --- a/nav2_system_tests/src/system/README.md +++ b/nav2_system_tests/src/system/README.md @@ -1,9 +1,9 @@ -# Navigation2 System Tests +# Nav2 System Tests This is a 'top level' system test which will use Gazebo to simulate a Robot moving from an known initial starting position to a goal pose. ## To run the test -First, you must build navigation2 including this package: +First, you must build Nav2 including this package: ``` colcon build --symlink-install ``` diff --git a/nav2_system_tests/src/system_failure/README.md b/nav2_system_tests/src/system_failure/README.md index 4afd4eaac34..1671ff9da4e 100644 --- a/nav2_system_tests/src/system_failure/README.md +++ b/nav2_system_tests/src/system_failure/README.md @@ -1,3 +1,3 @@ -# Navigation2 System Tests - Failure +# Nav2 System Tests - Failure High level system failures tests diff --git a/nav2_system_tests/src/updown/README.md b/nav2_system_tests/src/updown/README.md index abfbf0a9006..6756d524659 100644 --- a/nav2_system_tests/src/updown/README.md +++ b/nav2_system_tests/src/updown/README.md @@ -1,4 +1,4 @@ -# Navigation2 Updown Test +# Nav2 Updown Test This is a 'top level' system test which tests the lifecycle bringup and shutdown of the system. diff --git a/nav2_waypoint_follower/README.md b/nav2_waypoint_follower/README.md index 915e274ba49..49589b7dd6b 100644 --- a/nav2_waypoint_follower/README.md +++ b/nav2_waypoint_follower/README.md @@ -1,6 +1,6 @@ # Nav2 Waypoint Follower -The navigation2 waypoint follower is an example application of how to use the navigation action to complete some sort of orchestrated task. In this example, that task is to take a given set of waypoints and navigate to a set of positions in the order provided in the action request. The last waypoint in the waypoint array is the final position. +The Nav2 waypoint follower is an example application of how to use the navigation action to complete some sort of orchestrated task. In this example, that task is to take a given set of waypoints and navigate to a set of positions in the order provided in the action request. The last waypoint in the waypoint array is the final position. The package exposes the `follow_waypoints` action server of type `nav2_msgs/FollowWaypoints`. It is given an array of waypoints to visit, gives feedback about the current index of waypoint it is processing, and returns a list of waypoints it was unable to complete. @@ -13,7 +13,7 @@ There is a parameterization `stop_on_failure` whether to stop processing the way The ``nav2_waypoint_follower`` contains a waypoint following program with a plugin interface for specific task executors. This is useful if you need to go to a given location and complete a specific task like take a picture, pick up a box, or wait for user input. -It is a nice demo application for how to use navigation2 in a sample application. +It is a nice demo application for how to use Nav2 in a sample application. However, it could be used for more than just a sample application. There are 2 schools of thoughts for fleet managers / dispatchers. diff --git a/tools/build_all.sh b/tools/build_all.sh index 4b2e3c7d45c..0e29d60b656 100755 --- a/tools/build_all.sh +++ b/tools/build_all.sh @@ -16,7 +16,7 @@ fi set -e -# so you can call from anywhere in the navigation2_ws, ros2_ws, or deps branches +# so you can call from anywhere in the nav2_ws, ros2_ws, or deps branches while [[ "$PWD" =~ ros2_ws ]]; do cd ../ done @@ -25,7 +25,7 @@ while [[ "$PWD" =~ ros2_nav_dependencies_ws ]]; do cd ../ done -while [[ "$PWD" =~ navigation2_ws ]]; do +while [[ "$PWD" =~ nav2_ws ]]; do cd ../ done @@ -54,7 +54,7 @@ export ROSDISTRO_INDEX_URL='https://raw.githubusercontent.com/ros2/rosdistro/ros colcon build --symlink-install) # Build our code -cd $CWD/navigation2_ws +cd $CWD/nav2_ws export ROSDISTRO_INDEX_URL='https://raw.githubusercontent.com/ros2/rosdistro/ros2/index.yaml' (. $ROS2_SETUP_FILE && . $CWD/ros2_nav_dependencies_ws/install/setup.bash && colcon build --symlink-install) @@ -62,7 +62,7 @@ export ROSDISTRO_INDEX_URL='https://raw.githubusercontent.com/ros2/rosdistro/ros # Update the ROS1 bridge if test "$ENABLE_ROS1" = true && test "$ENABLE_ROS2" = true ; then cd $CWD - . navigation2_ws/install/setup.bash + . nav2_ws/install/setup.bash cd $CWD/ros2_ws colcon build --symlink-install --packages-select ros1_bridge --cmake-force-configure fi diff --git a/tools/initial_ros_setup.sh b/tools/initial_ros_setup.sh index 4be3a5f0ab1..d53a1f66aea 100755 --- a/tools/initial_ros_setup.sh +++ b/tools/initial_ros_setup.sh @@ -41,8 +41,8 @@ return_to_root_dir() { download_navstack() { echo "Downloading the ROS 2 navstack" - mkdir -p navigation2_ws/src - cd navigation2_ws + mkdir -p nav2_ws/src + cd nav2_ws if [ -f "custom_nav2.repos" ]; then #override default location for testing vcs import src < custom_nav2.repos else @@ -65,7 +65,7 @@ download_ros2_dependencies() { echo "Downloading the dependencies workspace" mkdir -p ros2_nav_dependencies_ws/src cd ros2_nav_dependencies_ws - vcs import src < ${CWD}/navigation2_ws/src/navigation2/tools/underlay.repos + vcs import src < ${CWD}/nav2_ws/src/navigation2/tools/underlay.repos return_to_root_dir } @@ -106,7 +106,7 @@ if [ "$REPLY" = "y" ]; then download_all rosdep_install if [ "$ENABLE_BUILD" = true ]; then - $CWD/navigation2_ws/src/navigation2/tools/build_all.sh + $CWD/nav2_ws/src/navigation2/tools/build_all.sh fi cd ${CWD} @@ -115,9 +115,9 @@ if [ "$REPLY" = "y" ]; then echo "Everything downloaded and built successfully." echo "To use the navstack source the setup.bash in the install folder" echo - echo "> source navigation2/install/setup.bash" + echo "> source nav2_ws/install/setup.bash" echo echo "To build the navstack you can either" - echo "1. Run 'colcon build --symlink-install' from the navigation2 folder" - echo "2. or run 'make' from navigation2/build/ folder" + echo "1. Run 'colcon build --symlink-install' from the nav2_ws folder" + echo "2. or run 'make' from nav2_ws/build/ folder" fi diff --git a/tools/run_sanitizers b/tools/run_sanitizers index 7ded4aa3595..fb263eda27c 100755 --- a/tools/run_sanitizers +++ b/tools/run_sanitizers @@ -5,7 +5,7 @@ # To use this script, make sure you have the colcon plugins installed according # to the instructions above. Then build ros2_ws and navstack_dependencies_ws. -# Source the navstack_dependencies_ws and then cd to the navigation2_ws. +# Source the navstack_dependencies_ws and then cd to the nav2_ws. # # Run this script by invoking navigation2/tools/run_sanitizers # Afterwards, there should be two files in the root of the workspace: