Skip to content

Commit b4e3bb8

Browse files
facontidavideMarc-Morcos
authored andcommitted
[behavior_tree] support both ports and blackboard (ros-navigation#4060)
* check result of blackboard->get and use halTree Signed-off-by: Davide Faconti <davide.faconti@gmail.com> * remove unused header Signed-off-by: Davide Faconti <davide.faconti@gmail.com> * BT: add port inputs when missing and use getInputPortOrBlackboard Signed-off-by: Davide Faconti <davide.faconti@gmail.com> * add description Signed-off-by: Davide Faconti <davide.faconti@gmail.com> * change return value of getInputPortOrBlackboard Signed-off-by: Davide Faconti <davide.faconti@gmail.com> * updated tree XML Signed-off-by: Davide Faconti <davide.faconti@gmail.com> --------- Signed-off-by: Davide Faconti <davide.faconti@gmail.com>
1 parent 896c436 commit b4e3bb8

34 files changed

+186
-113
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/behavior_tree_engine.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,6 @@
2323
#include "behaviortree_cpp_v3/behavior_tree.h"
2424
#include "behaviortree_cpp_v3/bt_factory.h"
2525
#include "behaviortree_cpp_v3/xml_parsing.h"
26-
#include "behaviortree_cpp_v3/loggers/bt_zmq_publisher.h"
2726

2827
#include "rclcpp/rclcpp.hpp"
2928

nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp

Lines changed: 42 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -132,20 +132,27 @@ inline std::set<int> convertFromString(StringView key)
132132
}
133133

134134
/**
135-
* @brief Return parameter value from behavior tree node or ros2 parameter file
135+
* @brief Return parameter value from behavior tree node or ros2 parameter file.
136136
* @param node rclcpp::Node::SharedPtr
137137
* @param param_name std::string
138138
* @param behavior_tree_node T2
139139
* @return <T1>
140140
*/
141-
template<typename T1, typename T2>
141+
template<typename T1, typename T2 = BT::TreeNode>
142142
T1 deconflictPortAndParamFrame(
143143
rclcpp::Node::SharedPtr node,
144144
std::string param_name,
145-
T2 * behavior_tree_node)
145+
const T2 * behavior_tree_node)
146146
{
147147
T1 param_value;
148-
if (!behavior_tree_node->getInput(param_name, param_value)) {
148+
bool param_from_input = behavior_tree_node->getInput(param_name, param_value);
149+
150+
if constexpr (std::is_same_v<T1, std::string>) {
151+
// not valid if port doesn't exist or it is an empty string
152+
param_from_input &= !param_value.empty();
153+
}
154+
155+
if (!param_from_input) {
149156
RCLCPP_DEBUG(
150157
node->get_logger(),
151158
"Parameter '%s' not provided by behavior tree xml file, "
@@ -162,6 +169,37 @@ T1 deconflictPortAndParamFrame(
162169
}
163170
}
164171

172+
/**
173+
* @brief Try reading an import port first, and if that doesn't work
174+
* fallback to reading directly the blackboard.
175+
* The blackboard must be passed explitly because config() is private in BT.CPP 4.X
176+
*
177+
* @param bt_node node
178+
* @param blackboard the blackboard ovtained with node->config().blackboard
179+
* @param param_name std::string
180+
* @param behavior_tree_node the node
181+
* @return <T>
182+
*/
183+
template<typename T> inline
184+
bool getInputPortOrBlackboard(
185+
const BT::TreeNode & bt_node,
186+
const BT::Blackboard & blackboard,
187+
const std::string & param_name,
188+
T & value)
189+
{
190+
if (bt_node.getInput<T>(param_name, value)) {
191+
return true;
192+
}
193+
if (blackboard.get<T>(param_name, value)) {
194+
return true;
195+
}
196+
return false;
197+
}
198+
199+
// Macro to remove boiler plate when using getInputPortOrBlackboard
200+
#define getInputOrBlackboard(name, value) \
201+
getInputPortOrBlackboard(*this, *(this->config().blackboard), name, value);
202+
165203
} // namespace BT
166204

167205
#endif // NAV2_BEHAVIOR_TREE__BT_UTILS_HPP_

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,12 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode
5757
*/
5858
static BT::PortsList providedPorts()
5959
{
60-
return {};
60+
return {
61+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
62+
"goals", "Vector of navigation goals"),
63+
BT::InputPort<geometry_msgs::msg::PoseStamped>(
64+
"goal", "Navigation goal"),
65+
};
6166
}
6267

6368
private:

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_updated_condition.hpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,12 @@ class GoalUpdatedCondition : public BT::ConditionNode
5454
*/
5555
static BT::PortsList providedPorts()
5656
{
57-
return {};
57+
return {
58+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
59+
"goals", "Vector of navigation goals"),
60+
BT::InputPort<geometry_msgs::msg::PoseStamped>(
61+
"goal", "Navigation goal"),
62+
};
5863
}
5964

6065
private:

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/initial_pose_received_condition.hpp

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__INITIAL_POSE_RECEIVED_CONDITION_HPP_
1616
#define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__INITIAL_POSE_RECEIVED_CONDITION_HPP_
1717

18+
#include <string>
1819
#include "behaviortree_cpp_v3/behavior_tree.h"
1920

2021
namespace nav2_behavior_tree
@@ -23,7 +24,21 @@ namespace nav2_behavior_tree
2324
* @brief A BT::ConditionNode that returns SUCCESS if initial pose
2425
* has been received and FAILURE otherwise
2526
*/
26-
BT::NodeStatus initialPoseReceived(BT::TreeNode & tree_node);
27-
}
27+
class InitialPoseReceived : public BT::ConditionNode
28+
{
29+
public:
30+
InitialPoseReceived(
31+
const std::string & name,
32+
const BT::NodeConfiguration & config);
33+
34+
static BT::PortsList providedPorts()
35+
{
36+
return {BT::InputPort<bool>("initial_pose_received")};
37+
}
38+
39+
BT::NodeStatus tick() override;
40+
};
41+
42+
} // namespace nav2_behavior_tree
2843

2944
#endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__INITIAL_POSE_RECEIVED_CONDITION_HPP_

nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,12 @@ class GoalUpdatedController : public BT::DecoratorNode
4848
*/
4949
static BT::PortsList providedPorts()
5050
{
51-
return {};
51+
return {
52+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
53+
"goals", "Vector of navigation goals"),
54+
BT::InputPort<geometry_msgs::msg::PoseStamped>(
55+
"goal", "Navigation goal"),
56+
};
5257
}
5358

5459
private:

nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,10 @@ class SpeedController : public BT::DecoratorNode
5757
BT::InputPort<double>("max_rate", 1.0, "Maximum rate"),
5858
BT::InputPort<double>("min_speed", 0.0, "Minimum speed"),
5959
BT::InputPort<double>("max_speed", 0.5, "Maximum speed"),
60+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
61+
"goals", "Vector of navigation goals"),
62+
BT::InputPort<geometry_msgs::msg::PoseStamped>(
63+
"goal", "Navigation goal"),
6064
};
6165
}
6266

nav2_behavior_tree/nav2_tree_nodes.xml

Lines changed: 13 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -224,9 +224,15 @@
224224
<input_port name="parent">Parent frame for transform</input_port>
225225
</Condition>
226226

227-
<Condition ID="GoalUpdated"/>
227+
<Condition ID="GoalUpdated">
228+
<input_port name="goal">Vector of navigation goals</input_port>
229+
<input_port name="goals">Navigation goal</input_port>
230+
</Condition>
228231

229-
<Condition ID="GlobalUpdatedGoal"/>
232+
<Condition ID="GlobalUpdatedGoal">
233+
<input_port name="goal">Vector of navigation goals</input_port>
234+
<input_port name="goals">Navigation goal</input_port>
235+
</Condition>
230236

231237
<Condition ID="IsBatteryLow">
232238
<input_port name="min_battery">Min battery % or voltage before triggering</input_port>
@@ -255,6 +261,7 @@
255261
</Condition>
256262

257263
<Condition ID="InitialPoseReceived">
264+
<input_port name="initial_pose_received">SUCCESS if initial_pose_received true</input_port>
258265
</Condition>
259266

260267
<Condition ID="IsPathValid">
@@ -313,6 +320,8 @@
313320
<input_port name="max_rate">Maximum rate</input_port>
314321
<input_port name="min_speed">Minimum speed</input_port>
315322
<input_port name="max_speed">Maximum speed</input_port>
323+
<input_port name="goal">Vector of navigation goals</input_port>
324+
<input_port name="goals">Navigation goal</input_port>
316325
</Decorator>
317326

318327
<Decorator ID="PathLongerOnApproach">
@@ -322,6 +331,8 @@
322331
</Decorator>
323332

324333
<Decorator ID="GoalUpdatedController">
334+
<input_port name="goal">Vector of navigation goals</input_port>
335+
<input_port name="goals">Navigation goal</input_port>
325336
</Decorator>
326337

327338
</TreeNodesModel>

nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ void RemovePassedGoals::initialize()
4141
auto node = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
4242
node->get_parameter("transform_tolerance", transform_tolerance_);
4343

44-
robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string, RemovePassedGoals>(
44+
robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string>(
4545
node, "robot_base_frame", this);
4646
}
4747

nav2_behavior_tree/plugins/condition/distance_traveled_condition.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,9 +43,9 @@ void DistanceTraveledCondition::initialize()
4343
tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>("tf_buffer");
4444
node_->get_parameter("transform_tolerance", transform_tolerance_);
4545

46-
global_frame_ = BT::deconflictPortAndParamFrame<std::string, DistanceTraveledCondition>(
46+
global_frame_ = BT::deconflictPortAndParamFrame<std::string>(
4747
node_, "global_frame", this);
48-
robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string, DistanceTraveledCondition>(
48+
robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string>(
4949
node_, "robot_base_frame", this);
5050
initialized_ = true;
5151
}

0 commit comments

Comments
 (0)