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

Adapt GoalUpdater to update goals as well #4771

Open
wants to merge 58 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
58 commits
Select commit Hold shift + click to select a range
4e878a2
Add IsStoppedBTNode
tonynajjar Nov 25, 2024
9139f9f
add topic name + reformat
tonynajjar Nov 25, 2024
c7ec42e
fix comment
tonynajjar Nov 25, 2024
5a8ea92
fix abs
tonynajjar Nov 25, 2024
9b5a93e
remove log
tonynajjar Nov 25, 2024
89c8d34
add getter functions for raw twist
tonynajjar Nov 26, 2024
c0098c4
remove unused code
tonynajjar Nov 26, 2024
18b8b76
use odomsmoother
tonynajjar Nov 26, 2024
5c0560a
fix formatting
tonynajjar Nov 26, 2024
66ed384
update groot
tonynajjar Nov 26, 2024
91230b2
Add test
tonynajjar Nov 27, 2024
d2c2db3
reset at success
tonynajjar Nov 27, 2024
c40896d
Merge branch 'add-is-stopped-BT-node'
tonynajjar Nov 27, 2024
11920d5
Merge branch 'ros-navigation:main' into main
tonynajjar Nov 28, 2024
e58ddfd
Merge branch 'main' into add-is-stopped-BT-node
tonynajjar Nov 28, 2024
37a5636
FIX velocity_threshold_
tonynajjar Nov 28, 2024
d237785
Fix stopped Node
tonynajjar Nov 28, 2024
5a4204f
Add tests to odometry_utils
tonynajjar Nov 28, 2024
0295ef9
fix linting
tonynajjar Nov 28, 2024
4c4da1a
Merge branch 'add-is-stopped-BT-node'
tonynajjar Nov 28, 2024
e4ef654
Merge branch 'ros-navigation:main' into main
tonynajjar Dec 3, 2024
58dc8bb
Merge branch 'ros-navigation:main' into main
tonynajjar Dec 4, 2024
fec198f
Adapt goalUpdater to modify goals as well
tonynajjar Nov 28, 2024
5a4f61f
fix formatting
tonynajjar Nov 28, 2024
13b47aa
fixes
tonynajjar Nov 28, 2024
0e9ebc4
change name of msg
tonynajjar Dec 3, 2024
db1b59d
Make input goals be Goals again for compatibility
tonynajjar Dec 5, 2024
4cd7ebf
fix
tonynajjar Dec 5, 2024
012a503
Revert "fix"
tonynajjar Dec 5, 2024
81fc608
refactoring
tonynajjar Dec 5, 2024
799045d
ament
tonynajjar Dec 5, 2024
c657a9f
ignore if no timestamps
tonynajjar Dec 9, 2024
f5bc15a
facepalm
tonynajjar Dec 9, 2024
9d2f2b1
update groot nodes
tonynajjar Dec 11, 2024
bdef481
Use PoseStampedArray
tonynajjar Dec 11, 2024
c0ba65d
Merge branch 'ros-navigation:main' into main
tonynajjar Dec 11, 2024
7c082e7
Merge remote-tracking branch 'origin/main' into use_posestampedarray
tonynajjar Dec 11, 2024
038f051
fix
tonynajjar Dec 11, 2024
622e6e1
fixes
tonynajjar Dec 11, 2024
27d0965
fix
tonynajjar Dec 11, 2024
15c1396
fix
tonynajjar Dec 11, 2024
0a5cc27
fix
tonynajjar Dec 11, 2024
cc16480
use geometry_msgs
tonynajjar Jan 7, 2025
fe0da93
fix import
tonynajjar Jan 7, 2025
1305c8e
use geometry_msgs
tonynajjar Jan 7, 2025
d96cd2d
more fixes
tonynajjar Jan 7, 2025
5d0b1e5
.
tonynajjar Jan 7, 2025
7a261b7
revert
tonynajjar Jan 7, 2025
36c21de
.
tonynajjar Jan 7, 2025
f1c4016
Merge branch 'ros-navigation:main' into main
tonynajjar Jan 7, 2025
80e0c17
Merge branch 'main' into use_posestampedarray
tonynajjar Jan 7, 2025
8c6c5c7
Merge branch 'main' into goals-updater-main
tonynajjar Jan 7, 2025
30aed4b
fix
tonynajjar Jan 7, 2025
9f4f804
add common_interfaces
tonynajjar Jan 7, 2025
4b891c1
fix
tonynajjar Jan 7, 2025
3247145
Merge branch 'use_posestampedarray' into goals-updater-main
tonynajjar Jan 7, 2025
bc1d94c
use PoseStampedArray
tonynajjar Jan 7, 2025
d5521f6
reformat
tonynajjar Jan 7, 2025
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
16 changes: 8 additions & 8 deletions nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#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 "geometry_msgs/msg/pose_stamped_array.hpp"
#include "nav_msgs/msg/path.hpp"

namespace BT
Expand Down Expand Up @@ -105,19 +105,19 @@ inline geometry_msgs::msg::PoseStamped convertFromString(const StringView key)
}

/**
* @brief Parse XML string to std::vector<geometry_msgs::msg::PoseStamped>
* @brief Parse XML string to geometry_msgs::msg::PoseStampedArray
* @param key XML string
* @return std::vector<geometry_msgs::msg::PoseStamped>
* @return geometry_msgs::msg::PoseStampedArray
*/
template<>
inline std::vector<geometry_msgs::msg::PoseStamped> convertFromString(const StringView key)
inline geometry_msgs::msg::PoseStampedArray 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)");
throw std::runtime_error("invalid number of fields for PoseStampedArray attribute)");
} else {
std::vector<geometry_msgs::msg::PoseStamped> poses;
geometry_msgs::msg::PoseStampedArray pose_stamped_array;
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]));
Expand All @@ -129,9 +129,9 @@ inline std::vector<geometry_msgs::msg::PoseStamped> convertFromString(const Stri
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);
pose_stamped_array.poses.push_back(pose_stamped);
}
return poses;
return pose_stamped_array;
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ class ComputePathThroughPosesAction
{
return providedBasicPorts(
{
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
"goals",
"Destinations to plan through"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,7 @@
#include <string>
#include <vector>

#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/quaternion.hpp"
#include "geometry_msgs/msg/pose_stamped_array.hpp"
#include "nav2_msgs/action/navigate_through_poses.hpp"
#include "nav2_behavior_tree/bt_action_node.hpp"

Expand Down Expand Up @@ -74,7 +73,7 @@ class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::Naviga
{
return providedBasicPorts(
{
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
"goals", "Destinations to plan through"),
BT::InputPort<std::string>("behavior_tree", "Behavior tree to run"),
BT::OutputPort<ActionResult::_error_code_type>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped_array.hpp"
#include "nav2_behavior_tree/bt_service_node.hpp"
#include "nav2_msgs/srv/get_costs.hpp"

Expand All @@ -30,8 +30,6 @@ namespace nav2_behavior_tree
class RemoveInCollisionGoals : public BtServiceNode<nav2_msgs::srv::GetCosts>
{
public:
typedef std::vector<geometry_msgs::msg::PoseStamped> Goals;

/**
* @brief A constructor for nav2_behavior_tree::RemoveInCollisionGoals
* @param service_node_name Service name this node creates a client for
Expand All @@ -54,23 +52,25 @@ class RemoveInCollisionGoals : public BtServiceNode<nav2_msgs::srv::GetCosts>
{
return providedBasicPorts(
{
BT::InputPort<Goals>("input_goals", "Original goals to remove from"),
BT::InputPort<geometry_msgs::msg::PoseStampedArray>("input_goals",
"Original goals to remove from"),
BT::InputPort<double>(
"cost_threshold", 254.0,
"Cost threshold for considering a goal in collision"),
BT::InputPort<bool>("use_footprint", true, "Whether to use footprint cost"),
BT::InputPort<bool>(
"consider_unknown_as_obstacle", false,
"Whether to consider unknown cost as obstacle"),
BT::OutputPort<Goals>("output_goals", "Goals with in-collision goals removed"),
BT::OutputPort<geometry_msgs::msg::PoseStampedArray>("output_goals",
"Goals with in-collision goals removed"),
});
}

private:
bool use_footprint_;
bool consider_unknown_as_obstacle_;
double cost_threshold_;
Goals input_goals_;
geometry_msgs::msg::PoseStampedArray input_goals_;
};

} // namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include <memory>
#include <string>

#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped_array.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/robot_utils.hpp"
#include "behaviortree_cpp/action_node.h"
Expand All @@ -31,8 +31,6 @@ namespace nav2_behavior_tree
class RemovePassedGoals : public BT::ActionNodeBase
{
public:
typedef std::vector<geometry_msgs::msg::PoseStamped> Goals;

RemovePassedGoals(
const std::string & xml_tag_name,
const BT::NodeConfiguration & conf);
Expand All @@ -45,8 +43,10 @@ class RemovePassedGoals : public BT::ActionNodeBase
static BT::PortsList providedPorts()
{
return {
BT::InputPort<Goals>("input_goals", "Original goals to remove viapoints from"),
BT::OutputPort<Goals>("output_goals", "Goals with passed viapoints removed"),
BT::InputPort<geometry_msgs::msg::PoseStampedArray>("input_goals",
"Original goals to remove viapoints from"),
BT::OutputPort<geometry_msgs::msg::PoseStampedArray>("output_goals",
"Goals with passed viapoints removed"),
BT::InputPort<double>("radius", 0.5, "radius to goal for it to be considered for removal"),
BT::InputPort<std::string>("global_frame", "Global frame"),
BT::InputPort<std::string>("robot_base_frame", "Robot base frame"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include "rclcpp/rclcpp.hpp"

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


Expand Down Expand Up @@ -59,7 +59,7 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
"goals", "Vector of navigation goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal", "Navigation goal"),
Expand All @@ -70,7 +70,7 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode
bool first_time;
rclcpp::Node::SharedPtr node_;
geometry_msgs::msg::PoseStamped goal_;
std::vector<geometry_msgs::msg::PoseStamped> goals_;
geometry_msgs::msg::PoseStampedArray goals_;
};

} // namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include <vector>

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

namespace nav2_behavior_tree
Expand Down Expand Up @@ -56,7 +56,7 @@ class GoalUpdatedCondition : public BT::ConditionNode
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
"goals", "Vector of navigation goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal", "Navigation goal"),
Expand All @@ -65,7 +65,7 @@ class GoalUpdatedCondition : public BT::ConditionNode

private:
geometry_msgs::msg::PoseStamped goal_;
std::vector<geometry_msgs::msg::PoseStamped> goals_;
geometry_msgs::msg::PoseStampedArray goals_;
};

} // namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class GoalUpdatedController : public BT::DecoratorNode
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
"goals", "Vector of navigation goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal", "Navigation goal"),
Expand All @@ -66,7 +66,7 @@ class GoalUpdatedController : public BT::DecoratorNode

bool goal_was_updated_;
geometry_msgs::msg::PoseStamped goal_;
std::vector<geometry_msgs::msg::PoseStamped> goals_;
geometry_msgs::msg::PoseStampedArray goals_;
};

} // namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
// Copyright (c) 2018 Intel Corporation
// Copyright (c) 2020 Francisco Martin Rico
// Copyright (c) 2024 Angsa Robotics
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -18,8 +19,10 @@

#include <memory>
#include <string>
#include <vector>

#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped_array.hpp"

#include "behaviortree_cpp/decorator_node.h"

Expand Down Expand Up @@ -52,9 +55,11 @@ class GoalUpdater : public BT::DecoratorNode
{
return {
BT::InputPort<geometry_msgs::msg::PoseStamped>("input_goal", "Original Goal"),
BT::OutputPort<geometry_msgs::msg::PoseStamped>(
"output_goal",
"Received Goal by subscription"),
BT::InputPort<geometry_msgs::msg::PoseStampedArray>("input_goals", "Original Goals"),
BT::OutputPort<geometry_msgs::msg::PoseStamped>("output_goal",
"Received Goal by subscription"),
BT::OutputPort<geometry_msgs::msg::PoseStampedArray>("output_goals",
"Received Goals by subscription")
};
}

Expand All @@ -71,9 +76,17 @@ class GoalUpdater : public BT::DecoratorNode
*/
void callback_updated_goal(const geometry_msgs::msg::PoseStamped::SharedPtr msg);

/**
* @brief Callback function for goals update topic
* @param msg Shared pointer to vector of geometry_msgs::msg::PoseStamped message
*/
void callback_updated_goals(const geometry_msgs::msg::PoseStampedArray::SharedPtr msg);

rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr goal_sub_;
rclcpp::Subscription<geometry_msgs::msg::PoseStampedArray>::SharedPtr goals_sub_;

geometry_msgs::msg::PoseStamped last_goal_received_;
geometry_msgs::msg::PoseStampedArray last_goals_received_;

rclcpp::Node::SharedPtr node_;
rclcpp::CallbackGroup::SharedPtr callback_group_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class SpeedController : public BT::DecoratorNode
BT::InputPort<double>("max_rate", 1.0, "Maximum rate"),
BT::InputPort<double>("min_speed", 0.0, "Minimum speed"),
BT::InputPort<double>("max_speed", 0.5, "Maximum speed"),
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
BT::InputPort<geometry_msgs::msg::PoseStampedArray>(
"goals", "Vector of navigation goals"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal", "Navigation goal"),
Expand Down Expand Up @@ -120,7 +120,7 @@ class SpeedController : public BT::DecoratorNode

// current goal
geometry_msgs::msg::PoseStamped goal_;
std::vector<geometry_msgs::msg::PoseStamped> goals_;
geometry_msgs::msg::PoseStampedArray goals_;
};

} // namespace nav2_behavior_tree
Expand Down
2 changes: 2 additions & 0 deletions nav2_behavior_tree/nav2_tree_nodes.xml
Original file line number Diff line number Diff line change
Expand Up @@ -328,7 +328,9 @@

<Decorator ID="GoalUpdater">
<input_port name="input_goal">Original goal in</input_port>
<input_port name="input_goals">Original goals in</input_port>
<output_port name="output_goal">Output goal set by subscription</output_port>
<output_port name="output_goals">Output goals set by subscription</output_port>
</Decorator>

<Decorator ID="SpeedController">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,15 +39,15 @@ void RemoveInCollisionGoals::on_tick()
getInput("input_goals", input_goals_);
getInput("consider_unknown_as_obstacle", consider_unknown_as_obstacle_);

if (input_goals_.empty()) {
if (input_goals_.poses.empty()) {
setOutput("output_goals", input_goals_);
should_send_request_ = false;
return;
}
request_ = std::make_shared<nav2_msgs::srv::GetCosts::Request>();
request_->use_footprint = use_footprint_;

for (const auto & goal : input_goals_) {
for (const auto & goal : input_goals_.poses) {
request_->poses.push_back(goal);
}
}
Expand All @@ -63,16 +63,16 @@ BT::NodeStatus RemoveInCollisionGoals::on_completion(
return BT::NodeStatus::FAILURE;
}

Goals valid_goal_poses;
geometry_msgs::msg::PoseStampedArray valid_goal_poses;
for (size_t i = 0; i < response->costs.size(); ++i) {
if ((response->costs[i] == 255 && !consider_unknown_as_obstacle_) ||
response->costs[i] < cost_threshold_)
{
valid_goal_poses.push_back(input_goals_[i]);
valid_goal_poses.poses.push_back(input_goals_.poses[i]);
}
}
// Inform if all goals have been removed
if (valid_goal_poses.empty()) {
if (valid_goal_poses.poses.empty()) {
RCLCPP_INFO(
node_->get_logger(),
"All goals are in collision and have been removed from the list");
Expand Down
12 changes: 6 additions & 6 deletions nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,10 @@ inline BT::NodeStatus RemovePassedGoals::tick()
initialize();
}

Goals goal_poses;
geometry_msgs::msg::PoseStampedArray goal_poses;
getInput("input_goals", goal_poses);

if (goal_poses.empty()) {
if (goal_poses.poses.empty()) {
setOutput("output_goals", goal_poses);
return BT::NodeStatus::SUCCESS;
}
Expand All @@ -61,21 +61,21 @@ inline BT::NodeStatus RemovePassedGoals::tick()

geometry_msgs::msg::PoseStamped current_pose;
if (!nav2_util::getCurrentPose(
current_pose, *tf_, goal_poses[0].header.frame_id, robot_base_frame_,
current_pose, *tf_, goal_poses.poses[0].header.frame_id, robot_base_frame_,
transform_tolerance_))
{
return BT::NodeStatus::FAILURE;
}

double dist_to_goal;
while (goal_poses.size() > 1) {
dist_to_goal = euclidean_distance(goal_poses[0].pose, current_pose.pose);
while (goal_poses.poses.size() > 1) {
dist_to_goal = euclidean_distance(goal_poses.poses[0].pose, current_pose.pose);

if (dist_to_goal > viapoint_achieved_radius_) {
break;
}

goal_poses.erase(goal_poses.begin());
goal_poses.poses.erase(goal_poses.poses.begin());
}

setOutput("output_goals", goal_poses);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ BT::NodeStatus GloballyUpdatedGoalCondition::tick()
return BT::NodeStatus::SUCCESS;
}

std::vector<geometry_msgs::msg::PoseStamped> current_goals;
geometry_msgs::msg::PoseStampedArray current_goals;
BT::getInputOrBlackboard("goals", current_goals);
geometry_msgs::msg::PoseStamped current_goal;
BT::getInputOrBlackboard("goal", current_goal);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ BT::NodeStatus GoalUpdatedCondition::tick()
return BT::NodeStatus::FAILURE;
}

std::vector<geometry_msgs::msg::PoseStamped> current_goals;
geometry_msgs::msg::PoseStampedArray current_goals;
geometry_msgs::msg::PoseStamped current_goal;
BT::getInputOrBlackboard("goals", current_goals);
BT::getInputOrBlackboard("goal", current_goal);
Expand Down
Loading
Loading