Skip to content

Commit 91290ef

Browse files
SteveMacenskict2034AlexeyMerzlyakovymd-stellaTony Najjar
authored
Iron Sync 3 - Sept 25 (#3837)
* Same orientation of coordinate frames in rviz ang gazebo (#3751) * rviz view straight in default xy orientation Signed-off-by: Christian Henkel <[email protected]> * gazebo orientation to match rviz Signed-off-by: Christian Henkel <[email protected]> * rotating in direction of view --------- Signed-off-by: Christian Henkel <[email protected]> * 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 * Update smac_planner_hybrid.cpp (#3760) * Fix missing mutex in PlannerServer::isPathValid (#3756) Signed-off-by: ymd-stella <[email protected]> * Rename PushRosNamespace to PushROSNamespace (#3763) * 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 <[email protected]> * 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 <[email protected]> --------- Co-authored-by: Steve Macenski <[email protected]> * use ros clock for wait (#3782) * use ROS clock for wait * fix backport issue --------- Co-authored-by: Guillaume Doisy <[email protected]> * 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 <[email protected]> --------- Co-authored-by: Guillaume Doisy <[email protected]> * Fixing typo in compute path through poses error codes (#3799) Signed-off-by: Mannucci, Anna (Bosch (CR)) <[email protected]> Co-authored-by: Mannucci, Anna (Bosch (CR)) <[email protected]> * Fixes for flaky WPF test (#3785) * Fixes for flaky WPF test: * New RewrittenYaml ability to add non-existing parameters * Prune distance fix for WPF test * Treat UNKNOWN status as error in WPF * Clear error codes after BT run * Remove unnecessary setInitialPose() from WPF test * Update nav2_waypoint_follower/src/waypoint_follower.cpp Co-authored-by: Steve Macenski <[email protected]> * Clean error code in any situation * Fix UNKNOWN WPF status handling --------- Co-authored-by: Steve Macenski <[email protected]> * Fix `min_points` comparison check (#3795) * Fix min_points checking * Expose action server result timeout as a parameter in bt navigator servers (#3787) * Expose action server default timeout in bt navigator servers * typo * duplicated comment * Expose result timeout in other actions * Proper timeout in bt node * Change default timeouts and remove comments * Remove comment in params file * uncrustify controller server * 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 * Fix CD configuration link reference (#3811) * Fix CD configuration page reference * Add CM work on 6th ROS Developers Day reference * some minor optimizations (#3821) * fix broken behaviortree doc link (#3822) Signed-off-by: Anton Kesy <[email protected]> * [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 * Add nav2_gps_waypoint_follower (#2814) * Add nav2_gps_waypoint_follower * use correct client node while calling it to spin * changed after 1'st review * apply requested changes * nav2_util::ServiceClient instead of CallbackGroup * another iteration to adress issues * update poses with function in the follower logic * add deps of robot_localization: diagnostics * fix typo in underlay.repo * add deps of robot_localization: geographic_info * minor clean-ups * bond_core version has been updated * rotation should also be considered in GPS WPFing * use better namings related to gps wpf orientation * handle cpplint errors * tf_listener needs to be initialized * apply requested changes * apply requested changes 3.0/3.0 * fix misplaced ";" * use run time param for gps transform timeout * change timeout var name * make use of stop_on_failure for GPS too * passing emptywaypont vectors are seen as failure * update warning for empty requests * consider utm -> map yaw offset * fix missed RCLCPP info * reorrect action;s name * waypoint stamps need to be updated * Fix segmentation fault on waypoint follower * Parametric frames and matrix multiplications * Replace oriented navsatfix for geographic_msgs/geopose * Remove deprecated oriented navsatfix message * Update branch name on robot_localization dependency * Fix parametric frames logic * Rename functions and adress comments * fix style in underlay.repos * remove duplicate word in underlay.repos * update dependency version of ompl * Template ServiceClient class to accept lifecycle node * Remove link to stackoverflow answer * Remove yaw offset compensation * Fix API change * Fix styling * Minor docs fixes * Fix style divergences * Style fixes * Style fixes v2 * Style fixes v3 * Remove unused variables and timestam overrides * restore goal timestamp override * WIP: Add follow gps waypoints test * Style fixes and gazebo world inertia fix * Reduce velocity smoother timeout * empty commit to rerun tests * Increment circle ci cache idx * Remove extra space in cmakelists.txt * Fix wrong usage of the global action server * update follow gps waypoints action definition * Fix action definition and looping * update params for the unit testing * WIP: update tests * fix tests * fixes to nav2 simple commander * add robot_localization localizer * Bring back from LL client * Update nav2_simple_commander/nav2_simple_commander/robot_navigator.py Co-authored-by: Steve Macenski <[email protected]> * missing argument in test function * small test error * style fixes nav2 simple commander * rename cartesian action server --------- Co-authored-by: jediofgever <[email protected]> Co-authored-by: Steve Macenski <[email protected]> * bumping iron from 1.2.2 to 1.2.3 for release * Update waypoint_follower.cpp --------- Signed-off-by: Christian Henkel <[email protected]> Signed-off-by: ymd-stella <[email protected]> Signed-off-by: Mannucci, Anna (Bosch (CR)) <[email protected]> Signed-off-by: Anton Kesy <[email protected]> Co-authored-by: Christian Henkel <[email protected]> Co-authored-by: Alexey Merzlyakov <[email protected]> Co-authored-by: ymd-stella <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: Hyunseok <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Anna Mannucci <[email protected]> Co-authored-by: Mannucci, Anna (Bosch (CR)) <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: Pedro Alejandro González <[email protected]> Co-authored-by: Anton Kesy <[email protected]> Co-authored-by: jediofgever <[email protected]>
1 parent faeb0d4 commit 91290ef

File tree

113 files changed

+2787
-254
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

113 files changed

+2787
-254
lines changed

nav2_amcl/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_amcl</name>
5-
<version>1.2.2</version>
5+
<version>1.2.3</version>
66
<description>
77
<p>
88
amcl is a probabilistic localization system for a robot moving in

nav2_behavior_tree/README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -63,4 +63,4 @@ The BehaviorTree engine has a run method that accepts an XML description of a BT
6363
6464
See the code in the [BT Navigator](../nav2_bt_navigator/src/bt_navigator.cpp) for an example usage of the BehaviorTreeEngine.
6565
66-
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/
66+
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/

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -196,6 +196,11 @@ class BtActionServer
196196
*/
197197
void populateErrorCode(typename std::shared_ptr<typename ActionT::Result> result);
198198

199+
/**
200+
* @brief Setting BT error codes to success. Used to clean blackboard between different BT runs
201+
*/
202+
void cleanErrorCodes();
203+
199204
// Action name
200205
std::string action_name_;
201206

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

+40-6
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
#include "nav2_msgs/action/navigate_to_pose.hpp"
2727
#include "nav2_behavior_tree/bt_action_server.hpp"
2828
#include "ament_index_cpp/get_package_share_directory.hpp"
29+
#include "nav2_util/node_utils.hpp"
2930

3031
namespace nav2_behavior_tree
3132
{
@@ -60,6 +61,9 @@ BtActionServer<ActionT>::BtActionServer(
6061
if (!node->has_parameter("default_server_timeout")) {
6162
node->declare_parameter("default_server_timeout", 20);
6263
}
64+
if (!node->has_parameter("action_server_result_timeout")) {
65+
node->declare_parameter("action_server_result_timeout", 900.0);
66+
}
6367

6468
std::vector<std::string> error_code_names = {
6569
"follow_path_error_code",
@@ -122,19 +126,38 @@ bool BtActionServer<ActionT>::on_configure()
122126
// Support for handling the topic-based goal pose from rviz
123127
client_node_ = std::make_shared<rclcpp::Node>("_", options);
124128

129+
// Declare parameters for common client node applications to share with BT nodes
130+
// Declare if not declared in case being used an external application, then copying
131+
// all of the main node's parameters to the client for BT nodes to obtain
132+
nav2_util::declare_parameter_if_not_declared(
133+
node, "global_frame", rclcpp::ParameterValue(std::string("map")));
134+
nav2_util::declare_parameter_if_not_declared(
135+
node, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
136+
nav2_util::declare_parameter_if_not_declared(
137+
node, "transform_tolerance", rclcpp::ParameterValue(0.1));
138+
nav2_util::copy_all_parameters(node, client_node_);
139+
140+
// set the timeout in seconds for the action server to discard goal handles if not finished
141+
double action_server_result_timeout;
142+
node->get_parameter("action_server_result_timeout", action_server_result_timeout);
143+
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
144+
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
145+
125146
action_server_ = std::make_shared<ActionServer>(
126147
node->get_node_base_interface(),
127148
node->get_node_clock_interface(),
128149
node->get_node_logging_interface(),
129150
node->get_node_waitables_interface(),
130-
action_name_, std::bind(&BtActionServer<ActionT>::executeCallback, this));
151+
action_name_, std::bind(&BtActionServer<ActionT>::executeCallback, this),
152+
nullptr, std::chrono::milliseconds(500), false, server_options);
131153

132154
// Get parameters for BT timeouts
133-
int timeout;
134-
node->get_parameter("bt_loop_duration", timeout);
135-
bt_loop_duration_ = std::chrono::milliseconds(timeout);
136-
node->get_parameter("default_server_timeout", timeout);
137-
default_server_timeout_ = std::chrono::milliseconds(timeout);
155+
int bt_loop_duration;
156+
node->get_parameter("bt_loop_duration", bt_loop_duration);
157+
bt_loop_duration_ = std::chrono::milliseconds(bt_loop_duration);
158+
int default_server_timeout;
159+
node->get_parameter("default_server_timeout", default_server_timeout);
160+
default_server_timeout_ = std::chrono::milliseconds(default_server_timeout);
138161

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

@@ -278,6 +302,8 @@ void BtActionServer<ActionT>::executeCallback()
278302
action_server_->terminate_all(result);
279303
break;
280304
}
305+
306+
cleanErrorCodes();
281307
}
282308

283309
template<class ActionT>
@@ -304,6 +330,14 @@ void BtActionServer<ActionT>::populateErrorCode(
304330
}
305331
}
306332

333+
template<class ActionT>
334+
void BtActionServer<ActionT>::cleanErrorCodes()
335+
{
336+
for (const auto & error_code : error_code_names_) {
337+
blackboard_->set<unsigned short>(error_code, 0); //NOLINT
338+
}
339+
}
340+
307341
} // namespace nav2_behavior_tree
308342

309343
#endif // NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_IMPL_HPP_

nav2_behavior_tree/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_behavior_tree</name>
5-
<version>1.2.2</version>
5+
<version>1.2.3</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<maintainer email="[email protected]">Carlos Orduno</maintainer>

nav2_behaviors/include/nav2_behaviors/plugins/wait.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class Wait : public TimedBehavior<WaitAction>
6363
CostmapInfoType getResourceInfo() override {return CostmapInfoType::LOCAL;}
6464

6565
protected:
66-
std::chrono::time_point<std::chrono::steady_clock> wait_end_;
66+
rclcpp::Time wait_end_;
6767
WaitAction::Feedback::SharedPtr feedback_;
6868
};
6969

nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp

+11-1
Original file line numberDiff line numberDiff line change
@@ -133,9 +133,19 @@ class TimedBehavior : public nav2_core::Behavior
133133
node->get_parameter("robot_base_frame", robot_base_frame_);
134134
node->get_parameter("transform_tolerance", transform_tolerance_);
135135

136+
if (!node->has_parameter("action_server_result_timeout")) {
137+
node->declare_parameter("action_server_result_timeout", 10.0);
138+
}
139+
140+
double action_server_result_timeout;
141+
node->get_parameter("action_server_result_timeout", action_server_result_timeout);
142+
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
143+
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
144+
136145
action_server_ = std::make_shared<ActionServer>(
137146
node, behavior_name_,
138-
std::bind(&TimedBehavior::execute, this));
147+
std::bind(&TimedBehavior::execute, this), nullptr, std::chrono::milliseconds(
148+
500), false, server_options);
139149

140150
local_collision_checker_ = local_collision_checker;
141151
global_collision_checker_ = global_collision_checker;

nav2_behaviors/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_behaviors</name>
5-
<version>1.2.2</version>
5+
<version>1.2.3</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Carlos Orduno</maintainer>
88
<maintainer email="[email protected]">Steve Macenski</maintainer>

nav2_behaviors/plugins/wait.cpp

+5-7
Original file line numberDiff line numberDiff line change
@@ -30,21 +30,19 @@ Wait::~Wait() = default;
3030

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

3837
ResultStatus Wait::onCycleUpdate()
3938
{
40-
auto current_point = std::chrono::steady_clock::now();
41-
auto time_left =
42-
std::chrono::duration_cast<std::chrono::nanoseconds>(wait_end_ - current_point).count();
39+
auto current_point = node_.lock()->now();
40+
auto time_left = wait_end_ - current_point;
4341

44-
feedback_->time_left = rclcpp::Duration(rclcpp::Duration::from_nanoseconds(time_left));
42+
feedback_->time_left = time_left;
4543
action_server_->publish_feedback(feedback_);
4644

47-
if (time_left > 0) {
45+
if (time_left.nanoseconds() > 0) {
4846
return ResultStatus{Status::RUNNING};
4947
} else {
5048
return ResultStatus{Status::SUCCEEDED};

nav2_bringup/README.md

+30-3
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,44 @@
11
# nav2_bringup
22

3-
The `nav2_bringup` package is an example bringup system for Nav2 applications.
3+
The `nav2_bringup` package is an example bringup system for Nav2 applications.
44

5-
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.
5+
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.
66

77
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.
88

99
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`.
1010

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

13-
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.
13+
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.
1414

1515
Note:
1616
* gazebo should be started with both libgazebo_ros_init.so and libgazebo_ros_factory.so to work correctly.
1717
* 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.
18+
19+
## Launch
20+
21+
### Multi-robot Simulation
22+
23+
This is how to launch multi-robot simulation with simple command line. Please see the Nav2 documentation for further augments.
24+
25+
#### Cloned
26+
27+
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.
28+
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}`.
29+
30+
Please refer to below examples.
31+
32+
```shell
33+
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}"
34+
```
35+
36+
#### Unique
37+
38+
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.
39+
40+
If you want to bringup more than two robots, you should modify the `unique_multi_tb3_simulation_launch.py` script.
41+
42+
```shell
43+
ros2 launch nav2_bringup unique_multi_tb3_simulation_launch.py
44+
```

nav2_bringup/launch/bringup_launch.py

+12-3
Original file line numberDiff line numberDiff line change
@@ -23,9 +23,9 @@
2323
from launch.launch_description_sources import PythonLaunchDescriptionSource
2424
from launch.substitutions import LaunchConfiguration, PythonExpression
2525
from launch_ros.actions import Node
26-
from launch_ros.actions import PushRosNamespace
26+
from launch_ros.actions import PushROSNamespace
2727
from launch_ros.descriptions import ParameterFile
28-
from nav2_common.launch import RewrittenYaml
28+
from nav2_common.launch import RewrittenYaml, ReplaceString
2929

3030

3131
def generate_launch_description():
@@ -54,6 +54,15 @@ def generate_launch_description():
5454
remappings = [('/tf', 'tf'),
5555
('/tf_static', 'tf_static')]
5656

57+
# Only it applys when `use_namespace` is True.
58+
# '<robot_namespace>' keyword shall be replaced by 'namespace' launch argument
59+
# in config file 'nav2_multirobot_params.yaml' as a default & example.
60+
# User defined config file should contain '<robot_namespace>' keyword for the replacements.
61+
params_file = ReplaceString(
62+
source_file=params_file,
63+
replacements={'<robot_namespace>': ('/', namespace)},
64+
condition=IfCondition(use_namespace))
65+
5766
configured_params = ParameterFile(
5867
RewrittenYaml(
5968
source_file=params_file,
@@ -113,7 +122,7 @@ def generate_launch_description():
113122

114123
# Specify the actions
115124
bringup_cmd_group = GroupAction([
116-
PushRosNamespace(
125+
PushROSNamespace(
117126
condition=IfCondition(use_namespace),
118127
namespace=namespace),
119128

0 commit comments

Comments
 (0)