Skip to content

Commit

Permalink
Jazzy sync 3: Nov 8, 2024 (#4747)
Browse files Browse the repository at this point in the history
* Adding non-charging dock support to docking server (for conveyers, pallots, etc) (#4627)

* adding non-charging dock support to docking server

Signed-off-by: Steve Macenski <[email protected]>

* docs and linting

* adding unit tests

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>

* Publish optimal trajectory as a Path message (#4640)

* Publish optimal trajectory as a Path message

Signed-off-by: Alyssa Agnissan <[email protected]>

* move publish_optimal_path to TrajectoryVisualizer + minor refactoring

Signed-off-by: Alyssa Agnissan <[email protected]>

* tests added for optimal path publication

Signed-off-by: Alyssa Agnissan <[email protected]>

* populate optimal path message in add()

Signed-off-by: Alyssa Agnissan <[email protected]>

* move path population in add_marker

Signed-off-by: Alyssa Agnissan <[email protected]>

---------

Signed-off-by: Alyssa Agnissan <[email protected]>

* [collision monitor] Select the observation sources used with each polygon (#4227)

* Collision monitor: select specific observation sources for polygon

Signed-off-by: asarazin <[email protected]>

* optimization

Signed-off-by: asarazin <[email protected]>

* add tests

Signed-off-by: asarazin <[email protected]>

---------

Signed-off-by: asarazin <[email protected]>
Co-authored-by: asarazin <[email protected]>

* Restore exported BT test utils header files after cmake revamp (#4652) (#4654)

Signed-off-by: Mike Wake <[email protected]>

* fix(bt_nodes): Correct default `server_timeout` behavior by using `getInputPortOrBlackboard()` (#4649)

Signed-off-by: Alan Xue <[email protected]>

* PoseStamped vector specialization (#4607)

* PoseStamped vector specialization

Signed-off-by: Tony Najjar <[email protected]>

* merge master

Signed-off-by: Tony Najjar <[email protected]>

* add path

Signed-off-by: Tony Najjar <[email protected]>

* fix size check

Signed-off-by: Tony Najjar <[email protected]>

* fix test

Signed-off-by: Tony Najjar <[email protected]>

* Revert "fix test"

This reverts commit 51f54eb.

* fix test

Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>

* [DWB] Option to limit velocity commands in trajectory generator (#4663)

* Option to limit vel cmd through traj generator

Signed-off-by: huiyulhy <[email protected]>

* Cleanup

Signed-off-by: huiyulhy <[email protected]>

* fix linting

Signed-off-by: huiyulhy <[email protected]>

* Update linting

Signed-off-by: huiyulhy <[email protected]>

* uncrustify

Signed-off-by: huiyulhy <[email protected]>

* uncrustify

Signed-off-by: huiyulhy <[email protected]>

---------

Signed-off-by: huiyulhy <[email protected]>

* Adding planner server timeout for costmap waiting (#4673)

* Adding planner server timeout for costmap waiting

Signed-off-by: Steve Macenski <[email protected]>

* Adding controller server's costmap timeout as well

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>

* fixing path longer on approach (#4622)

* fixing path longer on approach

Signed-off-by: Pradheep <[email protected]>

* removing the short circuit

Signed-off-by: Pradheep <[email protected]>

* adding additional layer of check

Signed-off-by: Pradheep <[email protected]>

---------

Signed-off-by: Pradheep <[email protected]>

* fix to bt action server logging before bt execution result being ready (#4677)

Signed-off-by: DreamWest <[email protected]>

* Correct paper name for graceful controller

Signed-off-by: Steve Macenski <[email protected]>

* Added missing action clients in robot_navigator(BasicNavigator) to destroy_node (#4698)

* fix: added assisted_teleop_client to robot_navigator(BasicNavigator) destroy_node

Signed-off-by: Tiwa Ojo <[email protected]>

* fix: added other missing action clients to robot_navigator(BasicNavigator) destroy_node

Signed-off-by: Tiwa Ojo <[email protected]>

---------

Signed-off-by: Tiwa Ojo <[email protected]>

* Fixing SGF in MPPI and Smoother (#4669)

Signed-off-by: Steve Macenski <[email protected]>

* fix: handle transition failures in all servers (#4708)

* fix: handle transition failures in planner/controller/smoother servers

Signed-off-by: Kemal Bektas <[email protected]>

* adding support for rest of servers + review comments

Signed-off-by: Steve Macenski <[email protected]>

* Replacing throws with error and failed lifecycle transitions

Signed-off-by: Steve Macenski <[email protected]>

* fix vel smoother unit tests

Signed-off-by: Steve Macenski <[email protected]>

* fixing docking server unit testing

Signed-off-by: Steve Macenski <[email protected]>

* fixing last bits

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Kemal Bektas <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Kemal Bektas <[email protected]>

* [RotationShimController] fix: rotate on short paths (#4716)

Add header data to goal for short paths.

Commit d8ae3c1 added the possibility to
the rotation shim controller to rotate towards the goal when the goal
was closer that the `forward_sampling_distance`. This feature was not
fully working as the goal was missing proper header data, causing the
rotation shim to give back control to the main controller.

Co-authored-by: agennart <[email protected]>

* Added parameter `rotate_to_heading_once` (#4721)

Signed-off-by: Daniil Khaninaev <[email protected]>

* [RotationShimController] fix: rotate to goal heading (#4724)

Add frame_id to goal when rotating towards goal heading, otherwise the
transform would fail. This bug was introduced in 30e2cde by not setting
the frame_id.

Signed-off-by: agennart <[email protected]>
Co-authored-by: agennart <[email protected]>

* [loopback_sim] Publish clock, [nav2_costmap_2d] Fix Qos (#4726)

* Publish /clock from loopback sim

Signed-off-by: Adi Vardi <[email protected]>

* [nav2_costmap_2d] Fix obstacle_layer trying to use RELIABLE QoS

Use QoS profile from rclcpp::SensorDataQoS() instead of rmw_qos_profile_t.
This solves an issue where the subscriber uses RELIABLE setting even when initialized from rmw_qos_profile_sensor_data.
In addition the Subscriber(..., rmw_qos_profile_t) constructor is deprecated in favor of Subscriber(..., rclcpp::QoS)

Signed-off-by: Adi Vardi <[email protected]>

* [nav2_smac_planner] fix typos

Signed-off-by: Adi Vardi <[email protected]>

* Use single quotes

Signed-off-by: Adi Vardi <[email protected]>

---------

Signed-off-by: Adi Vardi <[email protected]>

* Fix incorrect doxygen comment (#4741)

Signed-off-by: Ryan Friedman <[email protected]>

* Updating error logging in Smac collision detector object (#4743)

* Updating error logging in Smac configs

Signed-off-by: Steve Macenski <[email protected]>

* linting

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>

* [map_io] Replace std logs by rclcpp logs (#4720)

* replace std logs by rclcpp logs

Signed-off-by: Guillaume Doisy <[email protected]>

* RCLCPP_DEBUG to RCLCPP_INFO for visibility

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* manual backport to Jazzy of 6b2e244

Signed-off-by: Steve Macenski <[email protected]>

* bump to 1.3.3 for jazzy sync

Signed-off-by: Steve Macenski <[email protected]>

* fixing backport issue

Signed-off-by: Steve Macenski <[email protected]>

* fixing backport of docking linking changes

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: Alyssa Agnissan <[email protected]>
Signed-off-by: asarazin <[email protected]>
Signed-off-by: Mike Wake <[email protected]>
Signed-off-by: Alan Xue <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: huiyulhy <[email protected]>
Signed-off-by: Pradheep <[email protected]>
Signed-off-by: DreamWest <[email protected]>
Signed-off-by: Tiwa Ojo <[email protected]>
Signed-off-by: Kemal Bektas <[email protected]>
Signed-off-by: Daniil Khaninaev <[email protected]>
Signed-off-by: agennart <[email protected]>
Signed-off-by: Adi Vardi <[email protected]>
Signed-off-by: Ryan Friedman <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: alyquantillion <[email protected]>
Co-authored-by: anaelle-sw <[email protected]>
Co-authored-by: asarazin <[email protected]>
Co-authored-by: aosmw <[email protected]>
Co-authored-by: Alan <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Huiyu Leong <[email protected]>
Co-authored-by: Pradheep Krishna <[email protected]>
Co-authored-by: DreamWest <[email protected]>
Co-authored-by: Tiwa Ojo <[email protected]>
Co-authored-by: Kemal Bektas <[email protected]>
Co-authored-by: Saitama <[email protected]>
Co-authored-by: agennart <[email protected]>
Co-authored-by: Daniil Khaninaev <[email protected]>
Co-authored-by: Adi Vardi <[email protected]>
Co-authored-by: Ryan <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
  • Loading branch information
19 people authored Nov 8, 2024
1 parent 3e3506f commit 3140a6a
Show file tree
Hide file tree
Showing 132 changed files with 1,943 additions and 493 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.3.2</version>
<version>1.3.3</version>
<description>
<p>
amcl is a probabilistic localization system for a robot moving in
Expand Down
4 changes: 4 additions & 0 deletions nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -246,6 +246,10 @@ install(DIRECTORY test/utils/
DESTINATION include/${PROJECT_NAME}/utils/
)

install(DIRECTORY test/utils/
DESTINATION include/${PROJECT_NAME}/nav2_behavior_tree/test/utils
)

install(FILES nav2_tree_nodes.xml DESTINATION share/${PROJECT_NAME})
install(FILES ${GENERATED_DIR}/plugins_list.hpp DESTINATION include/${PROJECT_NAME})

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,9 +58,7 @@ class BtActionNode : public BT::ActionNodeBase
// Get the required items from the blackboard
auto bt_loop_duration =
config().blackboard->template get<std::chrono::milliseconds>("bt_loop_duration");
server_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);
getInputOrBlackboard("server_timeout", server_timeout_);
wait_for_service_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -310,18 +310,18 @@ void BtActionServer<ActionT>::executeCallback()

switch (rc) {
case nav2_behavior_tree::BtStatus::SUCCEEDED:
RCLCPP_INFO(logger_, "Goal succeeded");
action_server_->succeeded_current(result);
RCLCPP_INFO(logger_, "Goal succeeded");
break;

case nav2_behavior_tree::BtStatus::FAILED:
RCLCPP_ERROR(logger_, "Goal failed");
action_server_->terminate_current(result);
RCLCPP_ERROR(logger_, "Goal failed");
break;

case nav2_behavior_tree::BtStatus::CANCELED:
RCLCPP_INFO(logger_, "Goal canceled");
action_server_->terminate_all(result);
RCLCPP_INFO(logger_, "Goal canceled");
break;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,7 @@ class BtCancelActionNode : public BT::ActionNodeBase
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());

// Get the required items from the blackboard
server_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);
getInputOrBlackboard("server_timeout", server_timeout_);
wait_for_service_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,7 @@ class BtServiceNode : public BT::ActionNodeBase
// Get the required items from the blackboard
auto bt_loop_duration =
config().blackboard->template get<std::chrono::milliseconds>("bt_loop_duration");
server_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);
getInputOrBlackboard("server_timeout", server_timeout_);
wait_for_service_timeout_ =
config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");

Expand Down
66 changes: 66 additions & 0 deletions nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,15 @@

#include <string>
#include <set>
#include <vector>

#include "rclcpp/time.hpp"
#include "rclcpp/node.hpp"
#include "behaviortree_cpp/behavior_tree.h"
#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/quaternion.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav_msgs/msg/path.hpp"

namespace BT
{
Expand Down Expand Up @@ -102,6 +104,70 @@ inline geometry_msgs::msg::PoseStamped convertFromString(const StringView key)
}
}

/**
* @brief Parse XML string to std::vector<geometry_msgs::msg::PoseStamped>
* @param key XML string
* @return std::vector<geometry_msgs::msg::PoseStamped>
*/
template<>
inline std::vector<geometry_msgs::msg::PoseStamped> convertFromString(const StringView key)
{
// 9 real numbers separated by semicolons
auto parts = BT::splitString(key, ';');
if (parts.size() % 9 != 0) {
throw std::runtime_error("invalid number of fields for std::vector<PoseStamped> attribute)");
} else {
std::vector<geometry_msgs::msg::PoseStamped> poses;
for (size_t i = 0; i < parts.size(); i += 9) {
geometry_msgs::msg::PoseStamped pose_stamped;
pose_stamped.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[i]));
pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[i + 1]);
pose_stamped.pose.position.x = BT::convertFromString<double>(parts[i + 2]);
pose_stamped.pose.position.y = BT::convertFromString<double>(parts[i + 3]);
pose_stamped.pose.position.z = BT::convertFromString<double>(parts[i + 4]);
pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[i + 5]);
pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[i + 6]);
pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[i + 7]);
pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[i + 8]);
poses.push_back(pose_stamped);
}
return poses;
}
}

/**
* @brief Parse XML string to nav_msgs::msg::Path
* @param key XML string
* @return nav_msgs::msg::Path
*/
template<>
inline nav_msgs::msg::Path convertFromString(const StringView key)
{
// 9 real numbers separated by semicolons
auto parts = BT::splitString(key, ';');
if ((parts.size() - 2) % 9 != 0) {
throw std::runtime_error("invalid number of fields for Path attribute)");
} else {
nav_msgs::msg::Path path;
path.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[0]));
path.header.frame_id = BT::convertFromString<std::string>(parts[1]);
for (size_t i = 2; i < parts.size(); i += 9) {
geometry_msgs::msg::PoseStamped pose_stamped;
path.header.stamp = rclcpp::Time(BT::convertFromString<int64_t>(parts[i]));
pose_stamped.header.frame_id = BT::convertFromString<std::string>(parts[i + 1]);
pose_stamped.pose.position.x = BT::convertFromString<double>(parts[i + 2]);
pose_stamped.pose.position.y = BT::convertFromString<double>(parts[i + 3]);
pose_stamped.pose.position.z = BT::convertFromString<double>(parts[i + 4]);
pose_stamped.pose.orientation.x = BT::convertFromString<double>(parts[i + 5]);
pose_stamped.pose.orientation.y = BT::convertFromString<double>(parts[i + 6]);
pose_stamped.pose.orientation.z = BT::convertFromString<double>(parts[i + 7]);
pose_stamped.pose.orientation.w = BT::convertFromString<double>(parts[i + 8]);
path.poses.push_back(pose_stamped);
}
return path;
}
}

/**
* @brief Parse XML string to std::chrono::milliseconds
* @param key XML string
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/robot_utils.hpp"
#include "behaviortree_cpp/action_node.h"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "tf2_ros/buffer.h"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

#include "behaviortree_cpp/condition_node.h"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"


namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "rclcpp/rclcpp.hpp"
#include "behaviortree_cpp/condition_node.h"
#include "tf2_ros/buffer.h"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@

#include "behaviortree_cpp/condition_node.h"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <string>
#include "behaviortree_cpp/behavior_tree.h"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "rclcpp/rclcpp.hpp"
#include "behaviortree_cpp/condition_node.h"
#include "nav_msgs/msg/path.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "tf2_ros/buffer.h"

#include "behaviortree_cpp/decorator_node.h"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "nav2_util/odometry_utils.hpp"

#include "behaviortree_cpp/decorator_node.h"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
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.3.2</version>
<version>1.3.3</version>
<description>Nav2 behavior tree wrappers, nodes, and utilities</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<maintainer email="[email protected]">Carlos Orduno</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include "nav2_util/geometry_utils.hpp"

#include "nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include "nav2_util/geometry_utils.hpp"

#include "nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#include <string>

#include "nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include "nav2_util/node_utils.hpp"

#include "nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#include <string>
#include <vector>
#include "nav2_behavior_tree/plugins/condition/goal_updated_condition.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
// limitations under the License.

#include "nav2_behavior_tree/plugins/condition/initial_pose_received_condition.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
#include "behaviortree_cpp/decorator_node.h"

#include "nav2_behavior_tree/plugins/decorator/distance_controller.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "behaviortree_cpp/decorator_node.h"
#include "nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,10 @@ bool PathLongerOnApproach::isPathUpdated(
nav_msgs::msg::Path & new_path,
nav_msgs::msg::Path & old_path)
{
return new_path != old_path && old_path.poses.size() != 0 &&
return old_path.poses.size() != 0 &&
new_path.poses.size() != 0 &&
old_path.poses.back().pose == new_path.poses.back().pose;
new_path.poses.size() != old_path.poses.size() &&
old_path.poses.back().pose.position == new_path.poses.back().pose.position;
}

bool PathLongerOnApproach::isRobotInGoalProximity(
Expand Down Expand Up @@ -64,7 +65,7 @@ inline BT::NodeStatus PathLongerOnApproach::tick()

if (first_time_ == false) {
if (old_path_.poses.empty() || new_path_.poses.empty() ||
old_path_.poses.back() != new_path_.poses.back())
old_path_.poses.back().pose != new_path_.poses.back().pose)
{
first_time_ = true;
}
Expand Down
1 change: 0 additions & 1 deletion nav2_behavior_tree/plugins/decorator/speed_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include "nav2_util/geometry_utils.hpp"

#include "nav2_behavior_tree/plugins/decorator/speed_controller.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

namespace nav2_behavior_tree
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@

#include "utils/test_behavior_tree_fixture.hpp"
#include "nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"

using namespace std::chrono; // NOLINT
using namespace std::chrono_literals; // NOLINT
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,6 @@ class GoalUpdatedControllerTestFixture : public nav2_behavior_tree::BehaviorTree
poses1.push_back(goal1);
config_->blackboard->set("goal", goal1);
config_->blackboard->set("goals", poses1);
config_->input_ports["goals"] = "";
config_->input_ports["goal"] = "";
bt_node_ = std::make_shared<nav2_behavior_tree::GoalUpdatedController>(
"goal_updated_controller", *config_);
dummy_node_ = std::make_shared<nav2_behavior_tree::DummyNode>();
Expand Down
Loading

0 comments on commit 3140a6a

Please sign in to comment.