Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Iron Sync 3 - Sept 25 #3837

Merged
merged 22 commits into from
Sep 25, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
9483a0a
Same orientation of coordinate frames in rviz ang gazebo (#3751)
ct2034 Aug 10, 2023
31e3928
Fix flaky costmap filters tests: (#3754)
AlexeyMerzlyakov Aug 11, 2023
50d00a3
Update smac_planner_hybrid.cpp (#3760)
SteveMacenski Aug 16, 2023
845c30f
Fix missing mutex in PlannerServer::isPathValid (#3756)
ymd-stella Aug 16, 2023
c58b59f
Rename PushRosNamespace to PushROSNamespace (#3763)
Aug 17, 2023
16b7f26
Rewrite the scan topic costmap plugins for multi-robot(namespace) bef…
hyunseok-yang Aug 18, 2023
f19807a
use ros clock for wait (#3782)
doisyg Aug 29, 2023
c305fad
fixing external users of the BT action node template (#3792)
SteveMacenski Sep 1, 2023
c2bcf12
Fixing typo in compute path through poses error codes (#3799)
annamannucci Sep 7, 2023
0cc6567
Fixes for flaky WPF test (#3785)
AlexeyMerzlyakov Sep 7, 2023
bcbb1d6
Fix `min_points` comparison check (#3795)
tonynajjar Sep 8, 2023
a85466b
Expose action server result timeout as a parameter in bt navigator se…
pepisg Sep 9, 2023
8fe6363
Using Simple Commander API for multi robot systems (#3803)
SteveMacenski Sep 11, 2023
5d743a2
adding copy all params primitive for BT navigator (to ingest into rcl…
SteveMacenski Sep 13, 2023
a35b443
Fix CD configuration link reference (#3811)
AlexeyMerzlyakov Sep 18, 2023
537ca45
some minor optimizations (#3821)
SteveMacenski Sep 19, 2023
731c719
fix broken behaviortree doc link (#3822)
antonkesy Sep 19, 2023
0f2c083
[MPPI] complete minor optimaization with floating point calculations …
SteveMacenski Sep 20, 2023
cffc138
25% speed up of goal critic; 1% speed up from vy striding when not in…
SteveMacenski Sep 21, 2023
d72b851
Add nav2_gps_waypoint_follower (#2814)
pepisg Sep 21, 2023
26a3d50
bumping iron from 1.2.2 to 1.2.3 for release
SteveMacenski Sep 25, 2023
cd86381
Update waypoint_follower.cpp
SteveMacenski Sep 25, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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.2.2</version>
<version>1.2.3</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 @@ -196,6 +196,11 @@ class BtActionServer
*/
void populateErrorCode(typename std::shared_ptr<typename ActionT::Result> result);

/**
* @brief Setting BT error codes to success. Used to clean blackboard between different BT runs
*/
void cleanErrorCodes();

// Action name
std::string action_name_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,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 @@ -60,6 +61,9 @@ BtActionServer<ActionT>::BtActionServer(
if (!node->has_parameter("default_server_timeout")) {
node->declare_parameter("default_server_timeout", 20);
}
if (!node->has_parameter("action_server_result_timeout")) {
node->declare_parameter("action_server_result_timeout", 900.0);
}

std::vector<std::string> error_code_names = {
"follow_path_error_code",
Expand Down Expand Up @@ -122,19 +126,38 @@ 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_);

// set the timeout in seconds for the action server to discard goal handles if not finished
double action_server_result_timeout;
node->get_parameter("action_server_result_timeout", action_server_result_timeout);
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

action_server_ = std::make_shared<ActionServer>(
node->get_node_base_interface(),
node->get_node_clock_interface(),
node->get_node_logging_interface(),
node->get_node_waitables_interface(),
action_name_, std::bind(&BtActionServer<ActionT>::executeCallback, this));
action_name_, std::bind(&BtActionServer<ActionT>::executeCallback, this),
nullptr, std::chrono::milliseconds(500), false, server_options);

// Get parameters for BT timeouts
int timeout;
node->get_parameter("bt_loop_duration", timeout);
bt_loop_duration_ = std::chrono::milliseconds(timeout);
node->get_parameter("default_server_timeout", timeout);
default_server_timeout_ = std::chrono::milliseconds(timeout);
int bt_loop_duration;
node->get_parameter("bt_loop_duration", bt_loop_duration);
bt_loop_duration_ = std::chrono::milliseconds(bt_loop_duration);
int default_server_timeout;
node->get_parameter("default_server_timeout", default_server_timeout);
default_server_timeout_ = std::chrono::milliseconds(default_server_timeout);

// Get error code id names to grab off of the blackboard
error_code_names_ = node->get_parameter("error_code_names").as_string_array();
Expand Down Expand Up @@ -224,6 +247,7 @@ void BtActionServer<ActionT>::executeCallback()
{
if (!on_goal_received_callback_(action_server_->get_current_goal())) {
action_server_->terminate_current();
cleanErrorCodes();
return;
}

Expand Down Expand Up @@ -278,6 +302,8 @@ void BtActionServer<ActionT>::executeCallback()
action_server_->terminate_all(result);
break;
}

cleanErrorCodes();
}

template<class ActionT>
Expand All @@ -304,6 +330,14 @@ void BtActionServer<ActionT>::populateErrorCode(
}
}

template<class ActionT>
void BtActionServer<ActionT>::cleanErrorCodes()
{
for (const auto & error_code : error_code_names_) {
blackboard_->set<unsigned short>(error_code, 0); //NOLINT
}
}

} // namespace nav2_behavior_tree

#endif // NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_
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.2.2</version>
<version>1.2.3</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 @@ -63,7 +63,7 @@ class Wait : public TimedBehavior<WaitAction>
CostmapInfoType getResourceInfo() override {return CostmapInfoType::LOCAL;}

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

Expand Down
12 changes: 11 additions & 1 deletion nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,9 +133,19 @@ class TimedBehavior : public nav2_core::Behavior
node->get_parameter("robot_base_frame", robot_base_frame_);
node->get_parameter("transform_tolerance", transform_tolerance_);

if (!node->has_parameter("action_server_result_timeout")) {
node->declare_parameter("action_server_result_timeout", 10.0);
}

double action_server_result_timeout;
node->get_parameter("action_server_result_timeout", action_server_result_timeout);
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

action_server_ = std::make_shared<ActionServer>(
node, behavior_name_,
std::bind(&TimedBehavior::execute, this));
std::bind(&TimedBehavior::execute, this), nullptr, std::chrono::milliseconds(
500), false, server_options);

local_collision_checker_ = local_collision_checker;
global_collision_checker_ = global_collision_checker;
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.2.2</version>
<version>1.2.3</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;

ResultStatus 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 ResultStatus{Status::SUCCEEDED};
}

ResultStatus 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 ResultStatus{Status::RUNNING};
} else {
return ResultStatus{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
```
15 changes: 12 additions & 3 deletions nav2_bringup/launch/bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
from launch_ros.actions import PushRosNamespace
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 @@ -54,6 +54,15 @@ def generate_launch_description():
remappings = [('/tf', 'tf'),
('/tf_static', 'tf_static')]

# 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 Expand Up @@ -113,7 +122,7 @@ def generate_launch_description():

# Specify the actions
bringup_cmd_group = GroupAction([
PushRosNamespace(
PushROSNamespace(
condition=IfCondition(use_namespace),
namespace=namespace),

Expand Down
Loading