Skip to content

Commit 3a1d41e

Browse files
SteveMacenskiRyanf55FiIipejwallace42RBT22
authored
Iron sync 2, Aug 4, 1.2.2 (#3740)
* Only apply Wnon-virtual-dtor if the compile language is CXX (#3614) * https://stackoverflow.com/questions/25525047/cmake-generator-expression-differentiate-c-c-code Signed-off-by: Ryan Friedman <[email protected]> * Fix map not showing on rviz when navigation is launched with namespace (#3620) * Fix Wshadow errors and enforce it (#3617) * Fix Wshadow errors and enforce it Signed-off-by: Ryan Friedman <[email protected]> * Remove workaround for pluginlib * This was only needed because it was included transitively * By finding and linking properly, the compiler flags get propogated as SYSTEM correctly Signed-off-by: Ryan Friedman <[email protected]> --------- Signed-off-by: Ryan Friedman <[email protected]> * add-Wnull-dereference and fix warnings (#3622) Signed-off-by: Ryan Friedman <[email protected]> * updating mppi's path angle critic for optional bidirectionality (#3624) * updating mppi's path angle critic for optional bidirectionality * Update README.md * correct error message (#3631) * correct error message * clean up * cleanup * remove header * Let Navigators have different error codes (#3642) * Change ERROR to DEBUG * INFO message on init * format code * Replace newlines with spaces * fixing path angle critic's non-directional bias (#3632) * fixing path angle critic's non-directional bias * adding reformat * adapting goal critic for speed to goal (#3641) * adapting goal critic for speed to goal * retuning goal critic * add readme entries * Update critics_tests.cpp * Fix uninitialized value (#3651) * In NAV2, this warning is treated as an error Signed-off-by: Ryan Friedman <[email protected]> * Fix rviz panel node arguments (#3655) Signed-off-by: Nick Lamprianidis <[email protected]> * Reduce out-of-range log to DEBUG (#3656) * Adding nan twist rejection for velocity smoother and collision monitor (#3658) * adding nan twist rejection for velocity smoother and collision monitor * deref * Ceres exposes a namespaced export and recommends it in their docs (#3652) Signed-off-by: Ryan Friedman <[email protected]> * Enable multiple MPPI path angle modes depending on preferences in behavior (#3650) * fixing path angle critic's non-directional bias * adding reformat * handle linting * add utility unit tests * adding unit tests for path angle * MPPI: Support Exact Path Following For Feasible Plans (#3659) * alternative to path align critic for inversion control * fix default behavior (enforce_path_inversion: false) (#3643) Co-authored-by: Guillaume Doisy <[email protected]> * adding dyaw option for path alignment to incentivize following the path's intent where necessary * add docs for use path orientations * fix typo --------- Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> * Resolves 3646: Update CMAKE_COMPILER_IS_GNUCXX (#3662) * Resolves 3646: Update CMAKE_COMPILER_IS_GNUCXX * Update CMakeLists.txt * Fix smoother server tests (#3663) * Fix smoother server tests * Update test_smoother_server.cpp * fix some new build warnings from sync (#3674) * fix some new build warnings * fixing last issue * Update navigate_through_poses_action.hpp * adding unsigned int to tests * all to unsigned shorts * test new warning resolution * Update * convert unsigned shorts to uint16_t for linter * Fix costmap publisher test (#3679) * added printouts * ignore system tests * fix * cleanup * Update test_costmap_2d_publisher.cpp remove space * remove empty message (#3691) * Collision Monitor fixups (#3696) * Fix max_points -> min_points in parameters * Move robot_utils.hpp include to source where it actually using * Remove double-description of getTransform() * Use ParameterFile (allow_substs) (#3706) Signed-off-by: ymd-stella <[email protected]> * nav2_bt_navigator: log current location on navigate_to_pose action initialization (#3720) It is very useful to know the current location considered by the bt_navigator for debug purposes. * nav2_behaviors: export all available plugins (#3716) It allows external packages to include those headers and create child classes through inheritance. * changing costmap layers private to protected (#3722) * Update costmap_2d_ros.cpp (#3687) * updated nav2_behavior_tree test util install path (#3718) * launch linting (#3729) * adding error warnings around incorrect inflation layer setups in MPPI and Smac which impact performance substantially (#3728) * adding error warnings around incorrect inflation layer setups in MPPI and Smac which impact performance substantially * fix test failures * Update RewrittenYaml to support list rewrites (#3727) * allowing leaf key rewrites that aren't dcits (#3730) * adding checks on config and dynamic parameters for proper velocity and acceleration limits (#3731) * Fix Goal updater QoS (#3719) * Fix GoalUpdater QoS * Fixes * adding tolerance back in for smac lattice and hybrid-A* planners (#3734) * Completing Hybrid-A* visualization of expansion footprints PR (#3733) * smach_planner_hybrid: add support visualization for hybrid Astar * smac_planner_hyrid: revert some * smach_planner_hybrid: improving code quality * utils: add some useful functions * utils: fix mistake * nav2_smac_planner: fix format problem * utils: fix format and revise functions * smach_planner_hybrid: delete _viz_expansion parameter * smac_planner_hybrid: fix format * README: update parameter * utils: corrct mistake return * utils: make timestamp a const reference * nav2_smac_planner: correct format problem * add unit test functions * further detection of element equality * test_utils: add non-trival translation and rotation * smac_planner_hybrid: pass value instead of references * completing hybrid A* visualization --------- Co-authored-by: xianglunkai <[email protected]> * Update README.md (#3736) * Update README.md * Update README.md * sync iron to 1.2.2 to release --------- Signed-off-by: Ryan Friedman <[email protected]> Signed-off-by: Nick Lamprianidis <[email protected]> Signed-off-by: ymd-stella <[email protected]> Co-authored-by: Ryan <[email protected]> Co-authored-by: Filipe Cerveira <[email protected]> Co-authored-by: Joshua Wallace <[email protected]> Co-authored-by: RBT22 <[email protected]> Co-authored-by: Nick Lamprianidis <[email protected]> Co-authored-by: BriceRenaudeau <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Alexey Merzlyakov <[email protected]> Co-authored-by: ymd-stella <[email protected]> Co-authored-by: DylanDeCoeyer-Quimesis <[email protected]> Co-authored-by: Aaditya Ravindran <[email protected]> Co-authored-by: gyaanantia <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: xianglunkai <[email protected]>
1 parent 123e367 commit 3a1d41e

File tree

136 files changed

+1409
-359
lines changed

Some content is hidden

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

136 files changed

+1409
-359
lines changed

README.md

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,19 @@ please cite this work in your papers!
5555
}
5656
```
5757

58+
If you use **any** of the algorithms in Nav2 or the analysis of the algorithms in your work, please cite this work in your papers!
59+
60+
- S. Macenski, T. Moore, DV Lu, A. Merzlyakov, M. Ferguson, [**From the desks of ROS maintainers: A survey of modern & capable mobile robotics algorithms in the robot operating system 2**](https://arxiv.org/pdf/2307.15236.pdf), Robotics and Autonomous Systems, 2023.
61+
62+
```bibtex
63+
@article{macenski2023survey,
64+
title={From the desks of ROS maintainers: A survey of modern & capable mobile robotics algorithms in the robot operating system 2},
65+
author={S. Macenski, T. Moore, DV Lu, A. Merzlyakov, M. Ferguson},
66+
year={2023},
67+
journal = {Robotics and Autonomous Systems}
68+
}
69+
```
70+
5871
If you use the Regulated Pure Pursuit Controller algorithm or software from this repository, please cite this work in your papers!
5972

6073
- S. Macenski, S. Singh, F. Martin, J. Gines, [**Regulated Pure Pursuit for Robot Path Tracking**](https://arxiv.org/abs/2305.20026). Autonomous Robots, 2023.

nav2_amcl/package.xml

Lines changed: 1 addition & 1 deletion
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.1</version>
5+
<version>1.2.2</version>
66
<description>
77
<p>
88
amcl is a probabilistic localization system for a robot moving in

nav2_amcl/src/pf/eig3.c

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ static void tred2(double V[n][n], double d[n], double e[n])
4343
// Fortran subroutine in EISPACK.
4444

4545
int i, j, k;
46-
double f, g, h, hh;
46+
double f, g, hh;
4747
for (j = 0; j < n; j++) {
4848
d[j] = V[n - 1][j];
4949
}
@@ -122,7 +122,7 @@ static void tred2(double V[n][n], double d[n], double e[n])
122122
for (i = 0; i < n - 1; i++) {
123123
V[n - 1][i] = V[i][i];
124124
V[i][i] = 1.0;
125-
h = d[i + 1];
125+
const double h = d[i + 1];
126126
if (h != 0.0) {
127127
for (k = 0; k <= i; k++) {
128128
d[k] = V[k][i + 1] / h;

nav2_behavior_tree/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -224,7 +224,7 @@ install(DIRECTORY include/
224224
)
225225

226226
install(DIRECTORY test/utils/
227-
DESTINATION include/utils/
227+
DESTINATION include/${PROJECT_NAME}/utils/
228228
)
229229

230230
install(FILES nav2_tree_nodes.xml DESTINATION share/${PROJECT_NAME})

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

Lines changed: 23 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -67,16 +67,29 @@ BtActionServer<ActionT>::BtActionServer(
6767
};
6868

6969
if (!node->has_parameter("error_code_names")) {
70-
std::string error_codes_str;
71-
for (const auto & error_code : error_code_names) {
72-
error_codes_str += error_code + "\n";
70+
const rclcpp::ParameterValue value = node->declare_parameter(
71+
"error_code_names",
72+
rclcpp::PARAMETER_STRING_ARRAY);
73+
if (value.get_type() == rclcpp::PARAMETER_NOT_SET) {
74+
std::string error_codes_str;
75+
for (const auto & error_code : error_code_names) {
76+
error_codes_str += " " + error_code;
77+
}
78+
RCLCPP_WARN_STREAM(
79+
logger_, "Error_code parameters were not set. Using default values of:"
80+
<< error_codes_str + "\n"
81+
<< "Make sure these match your BT and there are not other sources of error codes you"
82+
"reported to your application");
83+
rclcpp::Parameter error_code_names_param("error_code_names", error_code_names);
84+
node->set_parameter(error_code_names_param);
85+
} else {
86+
error_code_names = value.get<std::vector<std::string>>();
87+
std::string error_codes_str;
88+
for (const auto & error_code : error_code_names) {
89+
error_codes_str += " " + error_code;
90+
}
91+
RCLCPP_INFO_STREAM(logger_, "Error_code parameters were set to:" << error_codes_str);
7392
}
74-
RCLCPP_WARN_STREAM(
75-
logger_, "Error_code parameters were not set. Using default values of: "
76-
<< error_codes_str
77-
<< "Make sure these match your BT and there are not other sources of error codes you want "
78-
"reported to your application");
79-
node->declare_parameter("error_code_names", error_code_names);
8093
}
8194
}
8295

@@ -279,7 +292,7 @@ void BtActionServer<ActionT>::populateErrorCode(
279292
highest_priority_error_code = current_error_code;
280293
}
281294
} catch (...) {
282-
RCLCPP_ERROR(
295+
RCLCPP_DEBUG(
283296
logger_,
284297
"Failed to get error code: %s from blackboard",
285298
error_code.c_str());

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__NAVIGATE_THROUGH_POSES_ACTION_HPP_
1717

1818
#include <string>
19+
#include <vector>
1920

2021
#include "geometry_msgs/msg/point.hpp"
2122
#include "geometry_msgs/msg/quaternion.hpp"
@@ -74,7 +75,8 @@ class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::Naviga
7475
{
7576
return providedBasicPorts(
7677
{
77-
BT::InputPort<geometry_msgs::msg::PoseStamped>("goals", "Destinations to plan through"),
78+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
79+
"goals", "Destinations to plan through"),
7880
BT::InputPort<std::string>("behavior_tree", "Behavior tree to run"),
7981
BT::OutputPort<ActionResult::_error_code_type>(
8082
"error_code_id", "The navigate through poses error code"),

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -34,14 +34,14 @@ class AreErrorCodesPresent : public BT::ConditionNode
3434
const BT::NodeConfiguration & conf)
3535
: BT::ConditionNode(condition_name, conf)
3636
{
37-
getInput<std::set<unsigned short>>("error_codes_to_check", error_codes_to_check_); //NOLINT
37+
getInput<std::set<uint16_t>>("error_codes_to_check", error_codes_to_check_); //NOLINT
3838
}
3939

4040
AreErrorCodesPresent() = delete;
4141

4242
BT::NodeStatus tick()
4343
{
44-
getInput<unsigned short>("error_code", error_code_); //NOLINT
44+
getInput<uint16_t>("error_code", error_code_); //NOLINT
4545

4646
if (error_codes_to_check_.find(error_code_) != error_codes_to_check_.end()) {
4747
return BT::NodeStatus::SUCCESS;
@@ -54,14 +54,14 @@ class AreErrorCodesPresent : public BT::ConditionNode
5454
{
5555
return
5656
{
57-
BT::InputPort<unsigned short>("error_code", "The active error codes"), //NOLINT
58-
BT::InputPort<std::set<unsigned short>>("error_codes_to_check", "Error codes to check")//NOLINT
57+
BT::InputPort<uint16_t>("error_code", "The active error codes"), //NOLINT
58+
BT::InputPort<std::set<uint16_t>>("error_codes_to_check", "Error codes to check")//NOLINT
5959
};
6060
}
6161

6262
protected:
63-
unsigned short error_code_; //NOLINT
64-
std::set<unsigned short> error_codes_to_check_; //NOLINT
63+
uint16_t error_code_; //NOLINT
64+
std::set<uint16_t> error_codes_to_check_; //NOLINT
6565
};
6666

6767
} // namespace nav2_behavior_tree

nav2_behavior_tree/package.xml

Lines changed: 1 addition & 1 deletion
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.1</version>
5+
<version>1.2.2</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<maintainer email="[email protected]">Carlos Orduno</maintainer>

nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp

Lines changed: 12 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ GoalUpdater::GoalUpdater(
4646
sub_option.callback_group = callback_group_;
4747
goal_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
4848
goal_updater_topic,
49-
10,
49+
rclcpp::SystemDefaultsQoS(),
5050
std::bind(&GoalUpdater::callback_updated_goal, this, _1),
5151
sub_option);
5252
}
@@ -59,8 +59,17 @@ inline BT::NodeStatus GoalUpdater::tick()
5959

6060
callback_group_executor_.spin_some();
6161

62-
if (rclcpp::Time(last_goal_received_.header.stamp) > rclcpp::Time(goal.header.stamp)) {
63-
goal = last_goal_received_;
62+
if (last_goal_received_.header.stamp != rclcpp::Time(0)) {
63+
auto last_goal_received_time = rclcpp::Time(last_goal_received_.header.stamp);
64+
auto goal_time = rclcpp::Time(goal.header.stamp);
65+
if (last_goal_received_time > goal_time) {
66+
goal = last_goal_received_;
67+
} else {
68+
RCLCPP_WARN(
69+
node_->get_logger(), "The timestamp of the received goal (%f) is older than the "
70+
"current goal (%f). Ignoring the received goal.",
71+
last_goal_received_time.seconds(), goal_time.seconds());
72+
}
6473
}
6574

6675
setOutput("output_goal", goal);

nav2_behavior_tree/test/plugins/condition/test_are_error_codes_present.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,8 @@ class AreErrorCodesPresentFixture : public nav2_behavior_tree::BehaviorTreeTestF
2727
using ActionGoal = Action::Goal;
2828
void SetUp()
2929
{
30-
int error_code = ActionGoal::NONE;
31-
std::set<unsigned short> error_codes_to_check = {ActionGoal::UNKNOWN}; //NOLINT
30+
uint16_t error_code = ActionGoal::NONE;
31+
std::set<uint16_t> error_codes_to_check = {ActionGoal::UNKNOWN}; //NOLINT
3232
config_->blackboard->set("error_code", error_code);
3333
config_->blackboard->set("error_codes_to_check", error_codes_to_check);
3434

@@ -58,7 +58,7 @@ std::shared_ptr<BT::Tree> AreErrorCodesPresentFixture::tree_ = nullptr;
5858

5959
TEST_F(AreErrorCodesPresentFixture, test_condition)
6060
{
61-
std::map<int, BT::NodeStatus> error_to_status_map = {
61+
std::map<uint16_t, BT::NodeStatus> error_to_status_map = {
6262
{ActionGoal::NONE, BT::NodeStatus::FAILURE},
6363
{ActionGoal::UNKNOWN, BT::NodeStatus::SUCCESS},
6464
};

0 commit comments

Comments
 (0)