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

Jazzy sync 3: Nov 8, 2024 #4747

Merged
merged 25 commits into from
Nov 8, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
9cf97b5
Adding non-charging dock support to docking server (for conveyers, pa…
SteveMacenski Aug 26, 2024
0217df4
Publish optimal trajectory as a Path message (#4640)
alyquantillion Aug 27, 2024
0a94280
[collision monitor] Select the observation sources used with each pol…
anaelle-sw Aug 29, 2024
8df2cb3
Restore exported BT test utils header files after cmake revamp (#4652…
aosmw Aug 31, 2024
4597214
fix(bt_nodes): Correct default `server_timeout` behavior by using `ge…
alanxuefei Sep 3, 2024
86eb079
PoseStamped vector specialization (#4607)
tonynajjar Sep 4, 2024
bc24be6
[DWB] Option to limit velocity commands in trajectory generator (#4663)
huiyulhy Sep 12, 2024
5e719cb
Adding planner server timeout for costmap waiting (#4673)
SteveMacenski Sep 12, 2024
c5e5077
fixing path longer on approach (#4622)
padhupradheep Sep 15, 2024
3a8cae2
fix to bt action server logging before bt execution result being read…
DreamWest Sep 15, 2024
79f517f
Correct paper name for graceful controller
SteveMacenski Sep 30, 2024
e3e8781
Added missing action clients in robot_navigator(BasicNavigator) to de…
tiwaojo Oct 1, 2024
c536b1c
Fixing SGF in MPPI and Smoother (#4669)
SteveMacenski Oct 3, 2024
bc94198
fix: handle transition failures in all servers (#4708)
SteveMacenski Oct 8, 2024
6bff7de
[RotationShimController] fix: rotate on short paths (#4716)
gennartan Oct 15, 2024
900df00
Added parameter `rotate_to_heading_once` (#4721)
ikhann Oct 16, 2024
dbf6c22
[RotationShimController] fix: rotate to goal heading (#4724)
gennartan Oct 17, 2024
077f73e
[loopback_sim] Publish clock, [nav2_costmap_2d] Fix Qos (#4726)
adivardi Nov 4, 2024
12b4233
Fix incorrect doxygen comment (#4741)
Ryanf55 Nov 6, 2024
edfb953
Updating error logging in Smac collision detector object (#4743)
SteveMacenski Nov 7, 2024
3425eb7
[map_io] Replace std logs by rclcpp logs (#4720)
doisyg Nov 7, 2024
172f9be
manual backport to Jazzy of 6b2e244
SteveMacenski Nov 8, 2024
7c9065a
bump to 1.3.3 for jazzy sync
SteveMacenski Nov 8, 2024
d8e09d3
fixing backport issue
SteveMacenski Nov 8, 2024
788dfd2
fixing backport of docking linking changes
SteveMacenski Nov 8, 2024
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.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
Loading