diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp index ddcec8f4df9..29da24fb0d2 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp @@ -132,22 +132,22 @@ inline std::set convertFromString(StringView key) } /** - * @brief Return parameter value from behavior tree node or ros2 parameter file + * @brief Return parameter value from behavior tree node or ros2 parameter file. * @param node rclcpp::Node::SharedPtr * @param param_name std::string - * @param behavior_tree_node the node - * @return + * @param behavior_tree_node T2 + * @return */ -template -T deconflictPortAndParamFrame( +template +T1 deconflictPortAndParamFrame( rclcpp::Node::SharedPtr node, std::string param_name, - const BT::TreeNode * behavior_tree_node) + const T2 * behavior_tree_node) { - T param_value; - bool param_from_input = behavior_tree_node->getInput(param_name, param_value); + T1 param_value; + bool param_from_input = behavior_tree_node->getInput(param_name, param_value); - if constexpr (std::is_same_v) { + if constexpr (std::is_same_v) { // not valid if port doesn't exist or it is an empty string param_from_input &= !param_value.empty(); } diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp index e0f64e854f7..299c38029f5 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp @@ -57,8 +57,7 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode */ static BT::PortsList providedPorts() { - return - { + return { BT::InputPort>("goals"), BT::InputPort("goal"), };