Skip to content

Commit

Permalink
Humble sync 7 August 4 1.1.9 (ros-navigation#3739)
Browse files Browse the repository at this point in the history
* Fix map not showing on rviz when navigation is launched with namespace (ros-navigation#3620)

* updating mppi's path angle critic for optional bidirectionality (ros-navigation#3624)

* updating mppi's path angle critic for optional bidirectionality

* Update README.md

* fixing path angle critic's non-directional bias (ros-navigation#3632)

* fixing path angle critic's non-directional bias

* adding reformat

* adapting goal critic for speed to goal (ros-navigation#3641)

* adapting goal critic for speed to goal

* retuning goal critic

* add readme entries

* Update critics_tests.cpp

* Fix uninitialized value (ros-navigation#3651)

* In NAV2, this warning is treated as an error

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>

* Fix rviz panel node arguments (ros-navigation#3655)

Signed-off-by: Nick Lamprianidis <info@nlamprian.me>

* Reduce out-of-range log to DEBUG (ros-navigation#3656)

* Adding nan twist rejection for velocity smoother and collision monitor (ros-navigation#3658)

* adding nan twist rejection for velocity smoother and collision monitor

* deref

* MPPI: Support Exact Path Following For Feasible Plans (ros-navigation#3659)

* alternative to path align critic for inversion control

* fix default behavior (enforce_path_inversion: false) (ros-navigation#3643)

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

* 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 <doisyg@users.noreply.github.com>
Co-authored-by: Guillaume Doisy <guillaume@dexory.com>

* Fix smoother server tests (ros-navigation#3663)

* Fix smoother server tests

* Update test_smoother_server.cpp

* nav2_bt_navigator: log current location on navigate_to_pose action initialization (ros-navigation#3720)

It is very useful to know the current location considered by the
bt_navigator for debug purposes.

* nav2_behaviors: export all available plugins (ros-navigation#3716)

It allows external packages to include those headers and create child
classes through inheritance.

* changing costmap layers private to protected (ros-navigation#3722)

* adding error warnings around incorrect inflation layer setups in MPPI and Smac which impact performance substantially (ros-navigation#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 (ros-navigation#3727)

* allowing leaf key rewrites that aren't dcits (ros-navigation#3730)

* adding checks on config and dynamic parameters for proper velocity and acceleration limits (ros-navigation#3731)

* Fix Goal updater QoS (ros-navigation#3719)

* Fix GoalUpdater QoS

* Fixes

* bumping Humble to 1.1.9 for release

* fix merge conflict resolution in collision monitor node

---------

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
Signed-off-by: Nick Lamprianidis <info@nlamprian.me>
Co-authored-by: Filipe Cerveira <filipecerveira@gmail.com>
Co-authored-by: Ryan <ryanfriedman5410+github@gmail.com>
Co-authored-by: Nick Lamprianidis <info@nlamprian.me>
Co-authored-by: BriceRenaudeau <48433002+BriceRenaudeau@users.noreply.github.com>
Co-authored-by: Guillaume Doisy <doisyg@users.noreply.github.com>
Co-authored-by: Guillaume Doisy <guillaume@dexory.com>
Co-authored-by: DylanDeCoeyer-Quimesis <102609575+DylanDeCoeyer-Quimesis@users.noreply.github.com>
Co-authored-by: gyaanantia <78275262+gyaanantia@users.noreply.github.com>
Co-authored-by: Tony Najjar <tony.najjar@logivations.com>
  • Loading branch information
10 people authored and RBT22 committed Oct 24, 2023
1 parent b09bb1b commit 8d6c30c
Show file tree
Hide file tree
Showing 99 changed files with 766 additions and 191 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.8</version>
<version>1.1.9</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/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.8</version>
<version>1.1.9</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
15 changes: 12 additions & 3 deletions nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ GoalUpdater::GoalUpdater(
sub_option.callback_group = callback_group_;
goal_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
goal_updater_topic,
10,
rclcpp::SystemDefaultsQoS(),
std::bind(&GoalUpdater::callback_updated_goal, this, _1),
sub_option);
}
Expand All @@ -59,8 +59,17 @@ inline BT::NodeStatus GoalUpdater::tick()

callback_group_executor_.spin_some();

if (rclcpp::Time(last_goal_received_.header.stamp) > rclcpp::Time(goal.header.stamp)) {
goal = last_goal_received_;
if (last_goal_received_.header.stamp != rclcpp::Time(0)) {
auto last_goal_received_time = rclcpp::Time(last_goal_received_.header.stamp);
auto goal_time = rclcpp::Time(goal.header.stamp);
if (last_goal_received_time > goal_time) {
goal = last_goal_received_;
} else {
RCLCPP_WARN(
node_->get_logger(), "The timestamp of the received goal (%f) is older than the "
"current goal (%f). Ignoring the received goal.",
last_goal_received_time.seconds(), goal_time.seconds());
}
}

setOutput("output_goal", goal);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,42 +95,101 @@ TEST_F(GoalUpdaterTestFixture, test_tick)
</root>)";

tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText(xml_txt, config_->blackboard));
auto goal_updater_pub =
node_->create_publisher<geometry_msgs::msg::PoseStamped>("goal_update", 10);

// create new goal and set it on blackboard
geometry_msgs::msg::PoseStamped goal;
goal.header.stamp = node_->now();
goal.pose.position.x = 1.0;
config_->blackboard->set("goal", goal);

// tick until node succeeds
while (tree_->rootNode()->status() != BT::NodeStatus::SUCCESS) {
tree_->rootNode()->executeTick();
}

// tick tree without publishing updated goal and get updated_goal
tree_->rootNode()->executeTick();
geometry_msgs::msg::PoseStamped updated_goal;
config_->blackboard->get("updated_goal", updated_goal);
}

EXPECT_EQ(updated_goal, goal);
TEST_F(GoalUpdaterTestFixture, test_older_goal_update)
{
// create tree
std::string xml_txt =
R"(
<root main_tree_to_execute = "MainTree" >
<BehaviorTree ID="MainTree">
<GoalUpdater input_goal="{goal}" output_goal="{updated_goal}">
<AlwaysSuccess/>
</GoalUpdater>
</BehaviorTree>
</root>)";

tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText(xml_txt, config_->blackboard));
auto goal_updater_pub =
node_->create_publisher<geometry_msgs::msg::PoseStamped>("goal_update", 10);

// create new goal and set it on blackboard
geometry_msgs::msg::PoseStamped goal;
goal.header.stamp = node_->now();
goal.pose.position.x = 1.0;
config_->blackboard->set("goal", goal);

// publish updated_goal older than goal
geometry_msgs::msg::PoseStamped goal_to_update;
goal_to_update.header.stamp = node_->now();
goal_to_update.header.stamp = rclcpp::Time(goal.header.stamp) - rclcpp::Duration(1, 0);
goal_to_update.pose.position.x = 2.0;

goal_updater_pub->publish(goal_to_update);
tree_->rootNode()->executeTick();
geometry_msgs::msg::PoseStamped updated_goal;
config_->blackboard->get("updated_goal", updated_goal);

// expect to succeed and not update goal
EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::SUCCESS);
EXPECT_EQ(updated_goal, goal);
}

TEST_F(GoalUpdaterTestFixture, test_get_latest_goal_update)
{
// create tree
std::string xml_txt =
R"(
<root main_tree_to_execute = "MainTree" >
<BehaviorTree ID="MainTree">
<GoalUpdater input_goal="{goal}" output_goal="{updated_goal}">
<AlwaysSuccess/>
</GoalUpdater>
</BehaviorTree>
</root>)";

tree_ = std::make_shared<BT::Tree>(factory_->createTreeFromText(xml_txt, config_->blackboard));
auto goal_updater_pub =
node_->create_publisher<geometry_msgs::msg::PoseStamped>("goal_update", 10);

auto start = node_->now();
while ((node_->now() - start).seconds() < 0.5) {
tree_->rootNode()->executeTick();
goal_updater_pub->publish(goal_to_update);
// create new goal and set it on blackboard
geometry_msgs::msg::PoseStamped goal;
goal.header.stamp = node_->now();
goal.pose.position.x = 1.0;
config_->blackboard->set("goal", goal);

rclcpp::spin_some(node_);
}
// publish updated_goal older than goal
geometry_msgs::msg::PoseStamped goal_to_update_1;
goal_to_update_1.header.stamp = node_->now();
goal_to_update_1.pose.position.x = 2.0;

geometry_msgs::msg::PoseStamped goal_to_update_2;
goal_to_update_2.header.stamp = node_->now();
goal_to_update_2.pose.position.x = 3.0;

goal_updater_pub->publish(goal_to_update_1);
goal_updater_pub->publish(goal_to_update_2);
tree_->rootNode()->executeTick();
geometry_msgs::msg::PoseStamped updated_goal;
config_->blackboard->get("updated_goal", updated_goal);

EXPECT_NE(updated_goal, goal);
EXPECT_EQ(updated_goal, goal_to_update);
// expect to succeed
EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::SUCCESS);
// expect to update goal with latest goal update
EXPECT_EQ(updated_goal, goal_to_update_2);
}

int main(int argc, char ** argv)
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
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.8</version>
<version>1.1.9</version>
<description>TODO</description>
<maintainer email="carlos.a.orduno@intel.com">Carlos Orduno</maintainer>
<maintainer email="stevenmacenski@gmail.com">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/plugins/assisted_teleop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include <utility>

#include "assisted_teleop.hpp"
#include "nav2_behaviors/plugins/assisted_teleop.hpp"
#include "nav2_util/node_utils.hpp"

namespace nav2_behaviors
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/plugins/back_up.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "back_up.hpp"
#include "nav2_behaviors/plugins/back_up.hpp"

namespace nav2_behaviors
{
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/plugins/drive_on_heading.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
// limitations under the License.

#include <memory>
#include "drive_on_heading.hpp"
#include "nav2_behaviors/plugins/drive_on_heading.hpp"

#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(nav2_behaviors::DriveOnHeading<>, nav2_core::Behavior)
2 changes: 1 addition & 1 deletion nav2_behaviors/plugins/spin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <memory>
#include <utility>

#include "spin.hpp"
#include "nav2_behaviors/plugins/spin.hpp"
#include "tf2/utils.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "nav2_util/node_utils.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/plugins/wait.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#include <chrono>
#include <memory>

#include "wait.hpp"
#include "nav2_behaviors/plugins/wait.hpp"

namespace nav2_behaviors
{
Expand Down
3 changes: 2 additions & 1 deletion nav2_bringup/launch/rviz_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,8 @@ def generate_launch_description():
namespace=namespace,
arguments=['-d', namespaced_rviz_config_file],
output='screen',
remappings=[('/tf', 'tf'),
remappings=[('/map', 'map'),
('/tf', 'tf'),
('/tf_static', 'tf_static'),
('/goal_pose', 'goal_pose'),
('/clicked_point', 'clicked_point'),
Expand Down
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.8</version>
<version>1.1.9</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
2 changes: 1 addition & 1 deletion nav2_bt_navigator/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_bt_navigator</name>
<version>1.1.8</version>
<version>1.1.9</version>
<description>TODO</description>
<maintainer email="michael.jeronimo@intel.com">Michael Jeronimo</maintainer>
<license>Apache-2.0</license>
Expand Down
9 changes: 8 additions & 1 deletion nav2_bt_navigator/src/navigators/navigate_to_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,8 +274,15 @@ NavigateToPoseNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
void
NavigateToPoseNavigator::initializeGoalPose(ActionT::Goal::ConstSharedPtr goal)
{
geometry_msgs::msg::PoseStamped current_pose;
nav2_util::getCurrentPose(
current_pose, *feedback_utils_.tf,
feedback_utils_.global_frame, feedback_utils_.robot_frame,
feedback_utils_.transform_tolerance);

RCLCPP_INFO(
logger_, "Begin navigating from current location to (%.2f, %.2f)",
logger_, "Begin navigating from current location (%.2f, %.2f) to (%.2f, %.2f)",
current_pose.pose.position.x, current_pose.pose.position.y,
goal->pose.pose.position.x, goal->pose.pose.position.y);

// Reset state for new action feedback
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "tf2_ros/transform_listener.h"

#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/robot_utils.hpp"

#include "nav2_collision_monitor/types.hpp"
#include "nav2_collision_monitor/polygon.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/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_collision_monitor</name>
<version>1.1.8</version>
<version>1.1.9</version>
<description>Collision Monitor</description>
<maintainer email="alexey.merzlyakov@samsung.com">Alexey Merzlyakov</maintainer>
<maintainer email="stevenmacenski@gmail.com">Steve Macenski</maintainer>
Expand Down
6 changes: 6 additions & 0 deletions nav2_collision_monitor/src/collision_monitor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,6 +148,12 @@ CollisionMonitor::on_shutdown(const rclcpp_lifecycle::State & /*state*/)

void CollisionMonitor::cmdVelInCallback(geometry_msgs::msg::Twist::ConstSharedPtr msg)
{
// If message contains NaN or Inf, ignore
if (!nav2_util::validateTwist(*msg)) {
RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
return;
}

process({msg->linear.x, msg->linear.y, msg->angular.z});
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/range.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ void Range::getData(

// Ignore data, if its range is out of scope of range sensor abilities
if (data_->range < data_->min_range || data_->range > data_->max_range) {
RCLCPP_WARN(
RCLCPP_DEBUG(
logger_,
"[%s]: Data range %fm is out of {%f..%f} sensor span. Ignoring...",
source_name_.c_str(), data_->range, data_->min_range, data_->max_range);
Expand Down
12 changes: 8 additions & 4 deletions nav2_common/nav2_common/launch/rewritten_yaml.py
Original file line number Diff line number Diff line change
Expand Up @@ -128,17 +128,21 @@ def updateYamlPathVals(self, yaml, yaml_key_list, rewrite_val):
yaml[key] = rewrite_val
break
key = yaml_key_list.pop(0)
yaml[key] = self.updateYamlPathVals(yaml.get(key, {}), yaml_key_list, rewrite_val)

if isinstance(yaml, list):
yaml[int(key)] = self.updateYamlPathVals(yaml[int(key)], yaml_key_list, rewrite_val)
else:
yaml[key] = self.updateYamlPathVals(yaml.get(key, {}), yaml_key_list, rewrite_val)
return yaml

def substitute_keys(self, yaml, key_rewrites):
if len(key_rewrites) != 0:
for key, val in yaml.items():
if isinstance(val, dict) and key in key_rewrites:
for key in list(yaml.keys()):
val = yaml[key]
if key in key_rewrites:
new_key = key_rewrites[key]
yaml[new_key] = yaml[key]
del yaml[key]
if isinstance(val, dict):
self.substitute_keys(val, key_rewrites)

def getYamlLeafKeys(self, yamlData):
Expand Down
2 changes: 1 addition & 1 deletion nav2_common/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_common</name>
<version>1.1.8</version>
<version>1.1.9</version>
<description>Common support functionality used throughout the navigation 2 stack</description>
<maintainer email="carl.r.delsey@intel.com">Carl Delsey</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_constrained_smoother/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_constrained_smoother</name>
<version>1.1.8</version>
<version>1.1.9</version>
<description>Ceres constrained smoother</description>
<maintainer email="vargovcik@robotechvision.com">Matej Vargovcik</maintainer>
<maintainer email="stevenmacenski@gmail.com">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/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_controller</name>
<version>1.1.8</version>
<version>1.1.9</version>
<description>Controller action interface</description>
<maintainer email="carl.r.delsey@intel.com">Carl Delsey</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_core/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_core</name>
<version>1.1.8</version>
<version>1.1.9</version>
<description>A set of headers for plugins core to the Nav2 stack</description>
<maintainer email="stevenmacenski@gmail.com">Steve Macenski</maintainer>
<maintainer email="carl.r.delsey@intel.com">Carl Delsey</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,6 @@ class InflationLayer : public Layer
*/
void onFootprintChanged() override;

private:
/**
* @brief Lookup pre-computed distances
* @param mx The x coordinate of the current cell
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ class RangeSensorLayer : public CostmapLayer
*/
void bufferIncomingRangeMsg(const sensor_msgs::msg::Range::SharedPtr range_message);

private:
protected:
/**
* @brief Processes all sensors into the costmap buffered from callbacks
*/
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ class StaticLayer : public CostmapLayer
*/
virtual void matchSize();

private:
protected:
/**
* @brief Get parameters of layer
*/
Expand Down
1 change: 0 additions & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,6 @@ class VoxelLayer : public ObstacleLayer
*/
virtual void resetMaps();

private:
/**
* @brief Use raycasting between 2 points to clear freespace
*/
Expand Down
Loading

0 comments on commit 8d6c30c

Please sign in to comment.