Skip to content

Commit

Permalink
[Humble] Sync 8 - Sept 25 (#3836)
Browse files Browse the repository at this point in the history
* Same orientation of coordinate frames in rviz ang gazebo (#3751)

* rviz view straight in default xy orientation

Signed-off-by: Christian Henkel <christian.henkel2@de.bosch.com>

* gazebo orientation to match rviz

Signed-off-by: Christian Henkel <christian.henkel2@de.bosch.com>

* rotating in direction of view

---------

Signed-off-by: Christian Henkel <christian.henkel2@de.bosch.com>

* Fix flaky costmap filters tests: (#3754)

1. Set forward_prune_distance to 1.0 to robot not getting lost
2. Correct map name for costmap filter tests

* Fix missing mutex in PlannerServer::isPathValid (#3756)

Signed-off-by: ymd-stella <world.applepie@gmail.com>

* Rewrite the scan topic costmap plugins for multi-robot(namespace) before launch navigation. (#3572)

* Make it possible to launch namspaced robot which rewrites `<robot_namespace>` to namespace.
- It allows to apply namespace automatically on specific target topic path in costmap plugins.

Add new nav2 params file for multi-robot(rewriting `<robot_namespace>`) as an example.
- nav2_multirobot_params_all.yaml

Modify nav2_common.ReplaceString
- add condition argument

* Update nav2_bringup/launch/bringup_launch.py

Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>

* Add new luanch script for multi-robot bringup

Rename luanch script for multi-robot simulation bringup

Add new nav2_common script
- Parse argument
- Parse multirobot pose

Update README.md

* Update README.md

Apply suggestions from code review

Fix pep257 erors

Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>

---------

Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>

* use ros clock for wait (#3782)

* use ROS clock for wait

* fix backport issue

---------

Co-authored-by: Guillaume Doisy <guillaume@dexory.com>

* fixing external users of the BT action node template (#3792)

* fixing external users of the BT action node template

* Update nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

Co-authored-by: Guillaume Doisy <doisyg@users.noreply.github.com>

---------

Co-authored-by: Guillaume Doisy <doisyg@users.noreply.github.com>

* Using Simple Commander API for multi robot systems (#3803)

* support multirobot namespaces

* add docs

* adding copy all params primitive for BT navigator (to ingest into rclcpp) (#3804)

* adding copy all params primitive

* fix linting

* lint

* I swear to god, this better be the last linting issue

* allowing params to be declared from yaml

* Update bt_navigator.cpp

* some minor optimizations (#3821)

* fix broken behaviortree doc link (#3822)

Signed-off-by: Anton Kesy <antonkesy@gmail.com>

* [MPPI] complete minor optimaization with floating point calculations (#3827)

* floating point calculations

* Update optimizer_unit_tests.cpp

* Update critics_tests.cpp

* Update critics_tests.cpp

* 25% speed up of goal critic; 1% speed up from vy striding when not in use

* bumping 1.1.9 to 1.1.10 for Humble release

---------

Signed-off-by: Christian Henkel <christian.henkel2@de.bosch.com>
Signed-off-by: ymd-stella <world.applepie@gmail.com>
Signed-off-by: Anton Kesy <antonkesy@gmail.com>
Co-authored-by: Christian Henkel <6976069+ct2034@users.noreply.github.com>
Co-authored-by: Alexey Merzlyakov <60094858+AlexeyMerzlyakov@users.noreply.github.com>
Co-authored-by: ymd-stella <7959916+ymd-stella@users.noreply.github.com>
Co-authored-by: Hyunseok <yanghyunseok@me.com>
Co-authored-by: Guillaume Doisy <doisyg@users.noreply.github.com>
Co-authored-by: Guillaume Doisy <guillaume@dexory.com>
Co-authored-by: Anton Kesy <antonkesy@gmail.com>
  • Loading branch information
8 people committed Sep 25, 2023
1 parent 9e63d43 commit b3474ca
Show file tree
Hide file tree
Showing 79 changed files with 893 additions and 162 deletions.
2 changes: 1 addition & 1 deletion nav2_amcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_amcl</name>
<version>1.1.9</version>
<version>1.1.10</version>
<description>
<p>
amcl is a probabilistic localization system for a robot moving in
Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -63,4 +63,4 @@ The BehaviorTree engine has a run method that accepts an XML description of a BT
See the code in the [BT Navigator](../nav2_bt_navigator/src/bt_navigator.cpp) for an example usage of the BehaviorTreeEngine.
For more information about the behavior tree nodes that are available in the default BehaviorTreeCPP library, see documentation here: https://www.behaviortree.dev/bt_basics/
For more information about the behavior tree nodes that are available in the default BehaviorTreeCPP library, see documentation here: https://www.behaviortree.dev/docs/learn-the-basics/bt_basics/
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "nav2_msgs/action/navigate_to_pose.hpp"
#include "nav2_behavior_tree/bt_action_server.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"
#include "nav2_util/node_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down Expand Up @@ -87,6 +88,17 @@ bool BtActionServer<ActionT>::on_configure()
// Support for handling the topic-based goal pose from rviz
client_node_ = std::make_shared<rclcpp::Node>("_", options);

// Declare parameters for common client node applications to share with BT nodes
// Declare if not declared in case being used an external application, then copying
// all of the main node's parameters to the client for BT nodes to obtain
nav2_util::declare_parameter_if_not_declared(
node, "global_frame", rclcpp::ParameterValue(std::string("map")));
nav2_util::declare_parameter_if_not_declared(
node, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
nav2_util::declare_parameter_if_not_declared(
node, "transform_tolerance", rclcpp::ParameterValue(0.1));
nav2_util::copy_all_parameters(node, client_node_);

action_server_ = std::make_shared<ActionServer>(
node->get_node_base_interface(),
node->get_node_clock_interface(),
Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_behavior_tree</name>
<version>1.1.9</version>
<version>1.1.10</version>
<description>TODO</description>
<maintainer email="michael.jeronimo@intel.com">Michael Jeronimo</maintainer>
<maintainer email="carlos.a.orduno@intel.com">Carlos Orduno</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/include/nav2_behaviors/plugins/wait.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class Wait : public TimedBehavior<WaitAction>
Status onCycleUpdate() override;

protected:
std::chrono::time_point<std::chrono::steady_clock> wait_end_;
rclcpp::Time wait_end_;
WaitAction::Feedback::SharedPtr feedback_;
};

Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_behaviors</name>
<version>1.1.9</version>
<version>1.1.10</version>
<description>TODO</description>
<maintainer email="carlos.a.orduno@intel.com">Carlos Orduno</maintainer>
<maintainer email="stevenmacenski@gmail.com">Steve Macenski</maintainer>
Expand Down
12 changes: 5 additions & 7 deletions nav2_behaviors/plugins/wait.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,21 +30,19 @@ Wait::~Wait() = default;

Status Wait::onRun(const std::shared_ptr<const WaitAction::Goal> command)
{
wait_end_ = std::chrono::steady_clock::now() +
rclcpp::Duration(command->time).to_chrono<std::chrono::nanoseconds>();
wait_end_ = node_.lock()->now() + rclcpp::Duration(command->time);
return Status::SUCCEEDED;
}

Status Wait::onCycleUpdate()
{
auto current_point = std::chrono::steady_clock::now();
auto time_left =
std::chrono::duration_cast<std::chrono::nanoseconds>(wait_end_ - current_point).count();
auto current_point = node_.lock()->now();
auto time_left = wait_end_ - current_point;

feedback_->time_left = rclcpp::Duration(rclcpp::Duration::from_nanoseconds(time_left));
feedback_->time_left = time_left;
action_server_->publish_feedback(feedback_);

if (time_left > 0) {
if (time_left.nanoseconds() > 0) {
return Status::RUNNING;
} else {
return Status::SUCCEEDED;
Expand Down
33 changes: 30 additions & 3 deletions nav2_bringup/README.md
Original file line number Diff line number Diff line change
@@ -1,17 +1,44 @@
# nav2_bringup

The `nav2_bringup` package is an example bringup system for Nav2 applications.
The `nav2_bringup` package is an example bringup system for Nav2 applications.

This is a very flexible example for nav2 bringup that can be modified for different maps/robots/hardware/worlds/etc. It is our expectation for an application specific robot system that you're mirroring `nav2_bringup` package and modifying it for your specific maps/robots/bringup needs. This is an applied and working demonstration for the default system bringup with many options that can be easily modified.
This is a very flexible example for nav2 bringup that can be modified for different maps/robots/hardware/worlds/etc. It is our expectation for an application specific robot system that you're mirroring `nav2_bringup` package and modifying it for your specific maps/robots/bringup needs. This is an applied and working demonstration for the default system bringup with many options that can be easily modified.

Usual robot stacks will have a `<robot_name>_nav` package with config/bringup files and this is that for the general case to base a specific robot system off of.

Dynamically composed bringup (based on [ROS2 Composition](https://docs.ros.org/en/galactic/Tutorials/Composition.html)) is optional for users. It can be used to compose all Nav2 nodes in a single process instead of launching these nodes separately, which is useful for embedded systems users that need to make optimizations due to harsh resource constraints. Dynamically composed bringup is used by default, but can be disabled by using the launch argument `use_composition:=False`.

* 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://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.

Note:
* gazebo should be started with both libgazebo_ros_init.so and libgazebo_ros_factory.so to work correctly.
* spawn_entity node could not remap /tf and /tf_static to tf and tf_static in the launch file yet, used only for multi-robot situations. Instead it should be done as remapping argument <remapping>/tf:=tf</remapping> <remapping>/tf_static:=tf_static</remapping> under ros2 tag in each plugin which publishs transforms in the SDF file. It is essential to differentiate the tf's of the different robot.

## Launch

### Multi-robot Simulation

This is how to launch multi-robot simulation with simple command line. Please see the Nav2 documentation for further augments.

#### Cloned

This allows to bring up multiple robots, cloning a single robot N times at different positions in the map. The parameter are loaded from `nav2_multirobot_params_all.yaml` file by default.
The multiple robots that consists of name and initial pose in YAML format will be set on the command-line. The format for each robot is `robot_name={x: 0.0, y: 0.0, yaw: 0.0, roll: 0.0, pitch: 0.0, yaw: 0.0}`.

Please refer to below examples.

```shell
ros2 launch nav2_bringup cloned_multi_tb3_simulation_launch.py robots:="robot1={x: 1.0, y: 1.0, yaw: 1.5707}; robot2={x: 1.0, y: 1.0, yaw: 1.5707}"
```

#### Unique

There are two robots including name and intitial pose are hard-coded in the launch script. Two separated unique robots are required params file (`nav2_multirobot_params_1.yaml`, `nav2_multirobot_params_2.yaml`) for each robot to bring up.

If you want to bringup more than two robots, you should modify the `unique_multi_tb3_simulation_launch.py` script.

```shell
ros2 launch nav2_bringup unique_multi_tb3_simulation_launch.py
```
11 changes: 10 additions & 1 deletion nav2_bringup/launch/bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
from launch_ros.actions import Node
from launch_ros.actions import PushRosNamespace
from launch_ros.descriptions import ParameterFile
from nav2_common.launch import RewrittenYaml
from nav2_common.launch import RewrittenYaml, ReplaceString


def generate_launch_description():
Expand Down Expand Up @@ -59,6 +59,15 @@ def generate_launch_description():
'use_sim_time': use_sim_time,
'yaml_filename': map_yaml_file}

# Only it applys when `use_namespace` is True.
# '<robot_namespace>' keyword shall be replaced by 'namespace' launch argument
# in config file 'nav2_multirobot_params.yaml' as a default & example.
# User defined config file should contain '<robot_namespace>' keyword for the replacements.
params_file = ReplaceString(
source_file=params_file,
replacements={'<robot_namespace>': ('/', namespace)},
condition=IfCondition(use_namespace))

configured_params = ParameterFile(
RewrittenYaml(
source_file=params_file,
Expand Down
174 changes: 174 additions & 0 deletions nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,174 @@
# Copyright (c) 2023 LG Electronics.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.


import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import (DeclareLaunchArgument, ExecuteProcess, GroupAction,
IncludeLaunchDescription, LogInfo)
from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, TextSubstitution
from nav2_common.launch import ParseMultiRobotPose


def generate_launch_description():
"""
Bring up the multi-robots with given launch arguments.
Launch arguments consist of robot name(which is namespace) and pose for initialization.
Keep general yaml format for pose information.
ex) robots:="robot1={x: 1.0, y: 1.0, yaw: 1.5707}; robot2={x: 1.0, y: 1.0, yaw: 1.5707}"
ex) robots:="robot3={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707};
robot4={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707}"
"""
# Get the launch directory
bringup_dir = get_package_share_directory('nav2_bringup')
launch_dir = os.path.join(bringup_dir, 'launch')

# Simulation settings
world = LaunchConfiguration('world')
simulator = LaunchConfiguration('simulator')

# On this example all robots are launched with the same settings
map_yaml_file = LaunchConfiguration('map')
params_file = LaunchConfiguration('params_file')
autostart = LaunchConfiguration('autostart')
rviz_config_file = LaunchConfiguration('rviz_config')
use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
use_rviz = LaunchConfiguration('use_rviz')
log_settings = LaunchConfiguration('log_settings', default='true')

# Declare the launch arguments
declare_world_cmd = DeclareLaunchArgument(
'world',
default_value=os.path.join(bringup_dir, 'worlds', 'world_only.model'),
description='Full path to world file to load')

declare_simulator_cmd = DeclareLaunchArgument(
'simulator',
default_value='gazebo',
description='The simulator to use (gazebo or gzserver)')

declare_map_yaml_cmd = DeclareLaunchArgument(
'map',
default_value=os.path.join(bringup_dir, 'maps', 'turtlebot3_world.yaml'),
description='Full path to map file to load')

declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
default_value=os.path.join(bringup_dir, 'params', 'nav2_multirobot_params_all.yaml'),
description='Full path to the ROS2 parameters file to use for all launched nodes')

declare_autostart_cmd = DeclareLaunchArgument(
'autostart', default_value='false',
description='Automatically startup the stacks')

declare_rviz_config_file_cmd = DeclareLaunchArgument(
'rviz_config',
default_value=os.path.join(bringup_dir, 'rviz', 'nav2_namespaced_view.rviz'),
description='Full path to the RVIZ config file to use.')

declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
'use_robot_state_pub',
default_value='True',
description='Whether to start the robot state publisher')

declare_use_rviz_cmd = DeclareLaunchArgument(
'use_rviz',
default_value='True',
description='Whether to start RVIZ')

# Start Gazebo with plugin providing the robot spawning service
start_gazebo_cmd = ExecuteProcess(
cmd=[simulator, '--verbose', '-s', 'libgazebo_ros_init.so',
'-s', 'libgazebo_ros_factory.so', world],
output='screen')

robots_list = ParseMultiRobotPose('robots').value()

# Define commands for launching the navigation instances
bringup_cmd_group = []
for robot_name in robots_list:
init_pose = robots_list[robot_name]
group = GroupAction([
LogInfo(msg=['Launching namespace=', robot_name, ' init_pose=', str(init_pose)]),

IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(launch_dir, 'rviz_launch.py')),
condition=IfCondition(use_rviz),
launch_arguments={'namespace': TextSubstitution(text=robot_name),
'use_namespace': 'True',
'rviz_config': rviz_config_file}.items()),

IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(bringup_dir,
'launch',
'tb3_simulation_launch.py')),
launch_arguments={'namespace': robot_name,
'use_namespace': 'True',
'map': map_yaml_file,
'use_sim_time': 'True',
'params_file': params_file,
'autostart': autostart,
'use_rviz': 'False',
'use_simulator': 'False',
'headless': 'False',
'use_robot_state_pub': use_robot_state_pub,
'x_pose': TextSubstitution(text=str(init_pose['x'])),
'y_pose': TextSubstitution(text=str(init_pose['y'])),
'z_pose': TextSubstitution(text=str(init_pose['z'])),
'roll': TextSubstitution(text=str(init_pose['roll'])),
'pitch': TextSubstitution(text=str(init_pose['pitch'])),
'yaw': TextSubstitution(text=str(init_pose['yaw'])),
'robot_name':TextSubstitution(text=robot_name), }.items())
])

bringup_cmd_group.append(group)

# Create the launch description and populate
ld = LaunchDescription()

# Declare the launch options
ld.add_action(declare_simulator_cmd)
ld.add_action(declare_world_cmd)
ld.add_action(declare_map_yaml_cmd)
ld.add_action(declare_params_file_cmd)
ld.add_action(declare_use_rviz_cmd)
ld.add_action(declare_autostart_cmd)
ld.add_action(declare_rviz_config_file_cmd)
ld.add_action(declare_use_robot_state_pub_cmd)

# Add the actions to start gazebo, robots and simulations
ld.add_action(start_gazebo_cmd)

ld.add_action(LogInfo(msg=['number_of_robots=', str(len(robots_list))]))

ld.add_action(LogInfo(condition=IfCondition(log_settings),
msg=['map yaml: ', map_yaml_file]))
ld.add_action(LogInfo(condition=IfCondition(log_settings),
msg=['params yaml: ', params_file]))
ld.add_action(LogInfo(condition=IfCondition(log_settings),
msg=['rviz config file: ', rviz_config_file]))
ld.add_action(LogInfo(condition=IfCondition(log_settings),
msg=['using robot state pub: ', use_robot_state_pub]))
ld.add_action(LogInfo(condition=IfCondition(log_settings),
msg=['autostart: ', autostart]))

for cmd in bringup_cmd_group:
ld.add_action(cmd)

return ld
2 changes: 1 addition & 1 deletion nav2_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_bringup</name>
<version>1.1.9</version>
<version>1.1.10</version>
<description>Bringup scripts and configurations for the Nav2 stack</description>
<maintainer email="michael.jeronimo@intel.com">Michael Jeronimo</maintainer>
<maintainer email="stevenmacenski@gmail.com">Steve Macenski</maintainer>
Expand Down
Loading

0 comments on commit b3474ca

Please sign in to comment.