Skip to content

Commit

Permalink
Merge branch 'ros-navigation:main' into fix-devcontainer
Browse files Browse the repository at this point in the history
  • Loading branch information
tonynajjar authored May 15, 2024
2 parents 6699cb5 + 2ae649b commit 476050c
Show file tree
Hide file tree
Showing 49 changed files with 320 additions and 128 deletions.
6 changes: 3 additions & 3 deletions .devcontainer/caddy/srv/nav2/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@

For more related documentation:

- [Nav2 Documentation](https://navigation.ros.org)
- [Development Guides](https://navigation.ros.org/development_guides)
- [Dev Containers](https://navigation.ros.org/development_guides/devcontainer_docs)
- [Nav2 Documentation](https://docs.nav2.org)
- [Development Guides](https://docs.nav2.org/development_guides)
- [Dev Containers](https://docs.nav2.org/development_guides/devcontainer_docs)

## Session Info

Expand Down
2 changes: 1 addition & 1 deletion .github/PULL_REQUEST_TEMPLATE.md
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
-->

#### For Maintainers: <!-- DO NOT EDIT OR REMOVE -->
- [ ] Check that any new parameters added are updated in navigation.ros.org
- [ ] Check that any new parameters added are updated in docs.nav2.org
- [ ] Check that any significant change is added to the migration guide
- [ ] Check that any new features **OR** changes to existing behaviors are reflected in the tuning guide
- [ ] Check that any new functions have Doxygen added
Expand Down
2 changes: 1 addition & 1 deletion .github/mergify.yml
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ pull_request_rules:
comment:
message: |
@{{author}}, please properly fill in PR template in the future. @stevemacenski, use this instead.
- [ ] Check that any new parameters added are updated in navigation.ros.org
- [ ] Check that any new parameters added are updated in docs.nav2.org
- [ ] Check that any significant change is added to the migration guide
- [ ] Check that any new features **OR** changes to existing behaviors are reflected in the tuning guide
- [ ] Check that any new functions have Doxygen added
Expand Down
26 changes: 13 additions & 13 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,24 +1,24 @@
# Nav2
[![GitHub Workflow Status](https://github.com/ros-planning/navigation2/actions/workflows/update_ci_image.yaml/badge.svg)](https://github.com/ros-planning/navigation2/actions/workflows/update_ci_image.yaml)
[![codecov](https://codecov.io/gh/ros-planning/navigation2/branch/main/graph/badge.svg?token=S3iRmypwlg)](https://codecov.io/gh/ros-planning/navigation2)
[![GitHub Workflow Status](https://github.com/ros-navigation/navigation2/actions/workflows/update_ci_image.yaml/badge.svg)](https://github.com/ros-navigation/navigation2/actions/workflows/update_ci_image.yaml)
[![codecov](https://codecov.io/gh/ros-navigation/navigation2/branch/main/graph/badge.svg?token=S3iRmypwlg)](https://codecov.io/gh/ros-navigation/navigation2)

<p align="center">
<img height="300" src="doc/nav2_logo.png" />
</p>

For detailed instructions on how to:
- [Getting Started](https://navigation.ros.org/getting_started/index.html)
- [Concepts](https://navigation.ros.org/concepts/index.html)
- [Build](https://navigation.ros.org/development_guides/build_docs/index.html#build)
- [Install](https://navigation.ros.org/development_guides/build_docs/index.html#install)
- [General Tutorials](https://navigation.ros.org/tutorials/index.html) and [Algorithm Developer Tutorials](https://navigation.ros.org/plugin_tutorials/index.html)
- [Configure](https://navigation.ros.org/configuration/index.html)
- [Navigation Plugins](https://navigation.ros.org/plugins/index.html)
- [Migration Guides](https://navigation.ros.org/migration/index.html)
- [Getting Started](https://docs.nav2.org/getting_started/index.html)
- [Concepts](https://docs.nav2.org/concepts/index.html)
- [Build](https://docs.nav2.org/development_guides/build_docs/index.html#build)
- [Install](https://docs.nav2.org/development_guides/build_docs/index.html#install)
- [General Tutorials](https://docs.nav2.org/tutorials/index.html) and [Algorithm Developer Tutorials](https://docs.nav2.org/plugin_tutorials/index.html)
- [Configure](https://docs.nav2.org/configuration/index.html)
- [Navigation Plugins](https://docs.nav2.org/plugins/index.html)
- [Migration Guides](https://docs.nav2.org/migration/index.html)
- [Container Images for Building Nav2](https://github.com/orgs/ros-planning/packages/container/package/navigation2)
- [Contribute](https://navigation.ros.org/development_guides/involvement_docs/index.html)
- [Contribute](https://docs.nav2.org/development_guides/involvement_docs/index.html)

Please visit our [documentation site](https://navigation.ros.org/). [Please visit our community Slack here](https://join.slack.com/t/navigation2/shared_invite/zt-hu52lnnq-cKYjuhTY~sEMbZXL8p9tOw) (if this link does not work, please contact maintainers to reactivate).
Please visit our [documentation site](https://docs.nav2.org/). [Please visit our community Slack here](https://join.slack.com/t/navigation2/shared_invite/zt-hu52lnnq-cKYjuhTY~sEMbZXL8p9tOw) (if this link does not work, please contact maintainers to reactivate).

If you need professional services related to Nav2, please contact Open Navigation at [email protected].

Expand Down Expand Up @@ -117,7 +117,7 @@ If you use the Regulated Pure Pursuit Controller algorithm or software from this
| Service | Humble | Iron | Main |
| :---: | :---: | :---: | :---: |
| ROS Build Farm | [![Build Status](https://build.ros2.org/job/Hdev__navigation2__ubuntu_jammy_amd64/badge/icon)](https://build.ros2.org/job/Hdev__navigation2__ubuntu_jammy_amd64/) | [![Build Status](https://build.ros2.org/job/Idev__navigation2__ubuntu_jammy_amd64/badge/icon)](https://build.ros2.org/job/Idev__navigation2__ubuntu_jammy_amd64/) | N/A |
| Circle CI | N/A | N/A | [![Build Status](https://circleci.com/gh/ros-planning/navigation2/tree/main.svg?style=svg)](https://circleci.com/gh/ros-planning/navigation2/tree/main) |
| Circle CI | N/A | N/A | [![Build Status](https://circleci.com/gh/ros-navigation/navigation2/tree/main.svg?style=svg)](https://circleci.com/gh/ros-navigation/navigation2/tree/main) |


| Package | Humble Source | Humble Debian | Iron Source | Iron Debian |
Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# AMCL
Adaptive Monte Carlo Localization (AMCL) is a probabilistic localization module which estimates the position and orientation (i.e. Pose) of a robot in a given known map using a 2D laser scanner. This is largely a refactored port from ROS 1 without any algorithmic changes.

See the [Configuration Guide Page](https://navigation.ros.org/configuration/packages/configuring-amcl.html) for more details about configurable settings and their meanings.
See the [Configuration Guide Page](https://docs.nav2.org/configuration/packages/configuring-amcl.html) for more details about configurable settings and their meanings.
7 changes: 2 additions & 5 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -524,11 +524,8 @@ AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::Sha

RCLCPP_INFO(get_logger(), "initialPoseReceived");

if (msg->header.frame_id == "") {
// This should be removed at some point
RCLCPP_WARN(
get_logger(),
"Received initial pose with empty frame_id. You should always supply a frame_id.");
if (!nav2_util::validateMsg(*msg)) {
RCLCPP_ERROR(get_logger(), "Received initialpose message is malformed. Rejecting.");
return;
}
if (nav2_util::strip_leading_slash(msg->header.frame_id) != global_frame_id_) {
Expand Down
1 change: 1 addition & 0 deletions nav2_amcl/src/pf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ target_include_directories(pf_lib PRIVATE ../include)
if(HAVE_DRAND48)
target_compile_definitions(pf_lib PRIVATE "HAVE_DRAND48")
endif()
target_link_libraries(pf_lib m)

install(TARGETS
pf_lib
Expand Down
4 changes: 2 additions & 2 deletions nav2_behavior_tree/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@ The nav2_behavior_tree module provides:
* Navigation-specific behavior tree nodes, and
* a generic BehaviorTreeEngine class that simplifies the integration of BT processing into ROS2 nodes for navigation or higher-level autonomy applications.

See its [Configuration Guide Page](https://navigation.ros.org/configuration/packages/configuring-bt-xml.html) for additional parameter descriptions and a list of XML nodes made available in this package. Also review the [Nav2 Behavior Tree Explanation](https://navigation.ros.org/behavior_trees/index.html) pages explaining more context on the default behavior trees and examples provided in this package. A [tutorial](https://navigation.ros.org/plugin_tutorials/docs/writing_new_bt_plugin.html) is also provided to explain how to create a simple BT plugin.
See its [Configuration Guide Page](https://docs.nav2.org/configuration/packages/configuring-bt-xml.html) for additional parameter descriptions and a list of XML nodes made available in this package. Also review the [Nav2 Behavior Tree Explanation](https://docs.nav2.org/behavior_trees/index.html) pages explaining more context on the default behavior trees and examples provided in this package. A [tutorial](https://docs.nav2.org/plugin_tutorials/docs/writing_new_bt_plugin.html) is also provided to explain how to create a simple BT plugin.

See the [Navigation Plugin list](https://navigation.ros.org/plugins/index.html) for a list of the currently known and available planner plugins.
See the [Navigation Plugin list](https://docs.nav2.org/plugins/index.html) for a list of the currently known and available planner plugins.

## The bt_action_node Template and the Behavior Tree Engine

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,12 +62,11 @@ inline BT::NodeStatus PathLongerOnApproach::tick()
getInput("prox_len", prox_len_);
getInput("length_factor", length_factor_);

if (!BT::isStatusActive(status())) {
// Reset the starting point since we're starting a new iteration of
// PathLongerOnApproach (moving from IDLE to RUNNING)
first_time_ = true;
if (first_time_ == false) {
if (old_path_.poses.back() != new_path_.poses.back()) {
first_time_ = true;
}
}

setStatus(BT::NodeStatus::RUNNING);

// Check if the path is updated and valid, compare the old and the new path length,
Expand Down
4 changes: 2 additions & 2 deletions nav2_behaviors/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@ The only required class a behavior must derive from is the `nav2_core/behavior.h

The value of the centralized behavior server is to **share resources** amongst several behaviors that would otherwise be independent nodes. Subscriptions to TF, costmaps, and more can be quite heavy and add non-trivial compute costs to a robot system. By combining these independent behaviors into a single server, they may share these resources while retaining complete independence in execution and interface.

See its [Configuration Guide Page](https://navigation.ros.org/configuration/packages/configuring-behavior-server.html) for additional parameter descriptions and a [tutorial about writing behaviors](https://navigation.ros.org/plugin_tutorials/docs/writing_new_behavior_plugin.html).
See its [Configuration Guide Page](https://docs.nav2.org/configuration/packages/configuring-behavior-server.html) for additional parameter descriptions and a [tutorial about writing behaviors](https://docs.nav2.org/plugin_tutorials/docs/writing_new_behavior_plugin.html).

See the [Navigation Plugin list](https://navigation.ros.org/plugins/index.html) for a list of the currently known and available planner plugins.
See the [Navigation Plugin list](https://docs.nav2.org/plugins/index.html) for a list of the currently known and available planner plugins.

The `TimedBehavior` template makes use of a [nav2_util::TwistPublisher](../nav2_util/README.md#twist-publisher-and-twist-subscriber-for-commanded-velocities).
The `AssistedTeleop` behavior makes use of a [nav2_util::TwistSubscriber](../nav2_util/README.md#twist-publisher-and-twist-subscriber-for-commanded-velocities).
2 changes: 1 addition & 1 deletion nav2_bringup/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ Dynamically composed bringup (based on [ROS2 Composition](https://docs.ros.org/

* Some discussions about performance improvement of composed bringup could be found here: https://discourse.ros.org/t/nav2-composition/22175.

To use, please see the Nav2 [Getting Started Page](https://navigation.ros.org/getting_started/index.html) on our documentation website. Additional [tutorials will help you](https://navigation.ros.org/tutorials/index.html) go from an initial setup in simulation to testing on a hardware robot, using SLAM, and more.
To use, please see the Nav2 [Getting Started Page](https://docs.nav2.org/getting_started/index.html) on our documentation website. Additional [tutorials will help you](https://docs.nav2.org/tutorials/index.html) go from an initial setup in simulation to testing on a hardware robot, using SLAM, and more.

Note:
* gazebo should be started with both libgazebo_ros_init.so and libgazebo_ros_factory.so to work correctly.
Expand Down
2 changes: 1 addition & 1 deletion nav2_bt_navigator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

The BT Navigator (Behavior Tree Navigator) module implements the NavigateToPose and NavigateThroughPoses task interfaces. It is a [Behavior Tree](https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/docs/BT_basics.md)-based implementation of navigation that is intended to allow for flexibility in the navigation task and provide a way to easily specify complex robot behaviors.

See its [Configuration Guide Page](https://navigation.ros.org/configuration/packages/configuring-bt-navigator.html) for additional parameter descriptions, as well as the [Nav2 Behavior Tree Explanation](https://navigation.ros.org/behavior_trees/index.html) pages explaining more context on the default behavior trees and examples provided in this package.
See its [Configuration Guide Page](https://docs.nav2.org/configuration/packages/configuring-bt-navigator.html) for additional parameter descriptions, as well as the [Nav2 Behavior Tree Explanation](https://docs.nav2.org/behavior_trees/index.html) pages explaining more context on the default behavior trees and examples provided in this package.

## Overview

Expand Down
4 changes: 2 additions & 2 deletions nav2_collision_monitor/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ The following diagram is showing the high-level design of Collision Monitor modu

### Configuration

Detailed configuration parameters, their description and how to setup a Collision Monitor could be found at its [Configuration Guide](https://navigation.ros.org/configuration/packages/configuring-collision-monitor.html) and [Using Collision Monitor tutorial](https://navigation.ros.org/tutorials/docs/using_collision_monitor.html) pages.
Detailed configuration parameters, their description and how to setup a Collision Monitor could be found at its [Configuration Guide](https://docs.nav2.org/configuration/packages/configuring-collision-monitor.html) and [Using Collision Monitor tutorial](https://docs.nav2.org/tutorials/docs/using_collision_monitor.html) pages.


### Metrics
Expand Down Expand Up @@ -94,6 +94,6 @@ The zones around the robot and the data sources are the same as for the Collisio

### Configuration

Detailed configuration parameters, their description and how to setup a Collision Detector could be found at its [Configuration Guide](https://navigation.ros.org/configuration/packages/collision_monitor/configuring-collision-detector-node.html).
Detailed configuration parameters, their description and how to setup a Collision Detector could be found at its [Configuration Guide](https://docs.nav2.org/configuration/packages/collision_monitor/configuring-collision-detector-node.html).

The `CollisionMonitor` node makes use of a [nav2_util::TwistSubscriber](../nav2_util/README.md#twist-publisher-and-twist-subscriber-for-commanded-velocities).
6 changes: 3 additions & 3 deletions nav2_constrained_smoother/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

A smoother plugin for `nav2_smoother` based on the original deprecated smoother in `nav2_smac_planner` by [Steve Macenski](https://www.linkedin.com/in/steve-macenski-41a985101/) and put into operational state by [**RoboTech Vision**](https://robotechvision.com/). Suitable for applications which need planned global path to be pushed away from obstacles and/or for Reeds-Shepp motion models.

See documentation on navigation.ros.org: https://navigation.ros.org/configuration/packages/configuring-constrained-smoother.html
See documentation on docs.nav2.org: https://docs.nav2.org/configuration/packages/configuring-constrained-smoother.html


Example of configuration (see indoor_navigation package of this repo for a full launch configuration):
Expand All @@ -26,13 +26,13 @@ smoother_server:
w_cost: 0.015 # weight to steer robot away from collision and cost
# Parameters used to improve obstacle avoidance near cusps (forward/reverse movement changes)
# See the [docs page](https://navigation.ros.org/configuration/packages/configuring-constrained-smoother) for further clarification
# See the [docs page](https://docs.nav2.org/configuration/packages/configuring-constrained-smoother) for further clarification
w_cost_cusp_multiplier: 3.0 # option to have higher weight during forward/reverse direction change which is often accompanied with dangerous rotations
cusp_zone_length: 2.5 # length of the section around cusp in which nodes use w_cost_cusp_multiplier (w_cost rises gradually inside the zone towards the cusp point, whose costmap weight equals w_cost*w_cost_cusp_multiplier)
# Points in robot frame to grab costmap values from. Format: [x1, y1, weight1, x2, y2, weight2, ...]
# IMPORTANT: Requires much higher number of iterations to actually improve the path. Uncomment only if you really need it (highly elongated/asymmetric robots)
# See the [docs page](https://navigation.ros.org/configuration/packages/configuring-constrained-smoother) for further clarification
# See the [docs page](https://docs.nav2.org/configuration/packages/configuring-constrained-smoother) for further clarification
# cost_check_points: [-0.185, 0.0, 1.0]
optimizer:
Expand Down
4 changes: 2 additions & 2 deletions nav2_controller/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@ The Nav2 Controller is a Task Server in Nav2 that implements the `nav2_msgs::act

An execution module implementing the `nav2_msgs::action::FollowPath` action server is responsible for generating command velocities for the robot, given the computed path from the planner module in `nav2_planner`. The nav2_controller package is designed to be loaded with multiple plugins for path execution. The plugins need to implement functions in the virtual base class defined in the `controller` header file in `nav2_core` package. It also contains progress checkers and goal checker plugins to abstract out that logic from specific controller implementations.

See the [Navigation Plugin list](https://navigation.ros.org/plugins/index.html) for a list of the currently known and available controller plugins.
See the [Navigation Plugin list](https://docs.nav2.org/plugins/index.html) for a list of the currently known and available controller plugins.

See its [Configuration Guide Page](https://navigation.ros.org/configuration/packages/configuring-controller-server.html) for additional parameter descriptions and a [tutorial about writing controller plugins](https://navigation.ros.org/plugin_tutorials/docs/writing_new_nav2controller_plugin.html).
See its [Configuration Guide Page](https://docs.nav2.org/configuration/packages/configuring-controller-server.html) for additional parameter descriptions and a [tutorial about writing controller plugins](https://docs.nav2.org/plugin_tutorials/docs/writing_new_nav2controller_plugin.html).

The `ControllerServer` makes use of a [nav2_util::TwistPublisher](../nav2_util/README.md#twist-publisher-and-twist-subscriber-for-commanded-velocities).
Loading

0 comments on commit 476050c

Please sign in to comment.