Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(behaviortree_cpp REQUIRED)
find_package(behaviortree_cpp_v3 REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
Expand All @@ -41,7 +41,7 @@ set(dependencies
nav2_msgs
std_srvs
tf2_ros
behaviortree_cpp
behaviortree_cpp_v3
)

set(executable_name behavior_tree_example)
Expand Down
4 changes: 2 additions & 2 deletions include/ros2_behavior_tree_example/bt_ros_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"

#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp/bt_factory.h"
#include "behaviortree_cpp_v3/behavior_tree.h"
#include "behaviortree_cpp_v3/bt_factory.h"

namespace polymath
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#define LOG_STATUS_BT_NODE_H_

#include <string>
#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp_v3/behavior_tree.h"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "std_msgs/msg/int32.hpp"
Expand All @@ -23,7 +23,7 @@ namespace bt_ros_example
/// @param action_name Name for the XML tag for this node
/// @param conf BT Node Configuration
///
LogStatusNode(const std::string & action_name, const BT::NodeConfig & conf);
LogStatusNode(const std::string & action_name, const BT::NodeConfiguration & conf);

~LogStatusNode();

Expand Down
4 changes: 2 additions & 2 deletions include/ros2_behavior_tree_example/plugins/ping_bt_node.hpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef PING_BT_NODE_H_
#define PING_BT_NODE_H_

#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp_v3/behavior_tree.h"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "std_msgs/msg/int32.hpp"
Expand All @@ -23,7 +23,7 @@ namespace bt_ros_example
/// @param action_name Name for the XML tag for this node
/// @param conf BT Node Configuration
///
PingNode(const std::string & action_name, const BT::NodeConfig & conf);
PingNode(const std::string & action_name, const BT::NodeConfiguration & conf);
~PingNode();

///
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef PONG_RECEIVED_NODE_H_
#define PONG_RECEIVED_NODE_H_

#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp_v3/behavior_tree.h"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "std_msgs/msg/int32.hpp"
Expand All @@ -22,7 +22,7 @@ namespace bt_ros_example
/// @param condition_name Name for the XML tag for this node
/// @param conf BT Node Configuration
///
PongReceivedNode(const std::string & condition_name, const BT::NodeConfig & conf);
PongReceivedNode(const std::string & condition_name, const BT::NodeConfiguration & conf);
PongReceivedNode() = delete;
~PongReceivedNode();

Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef PONG_RECEIVED_EXECUTOR_NODE_
#define PONG_RECEIVED_EXECUTOR_NODE_

#include "behaviortree_cpp/behavior_tree.h"
#include "behaviortree_cpp_v3/behavior_tree.h"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "std_msgs/msg/int32.hpp"
Expand All @@ -22,7 +22,7 @@ namespace bt_ros_example
/// @param condition_name Name for the XML tag for this node
/// @param conf BT Node Configuration
///
PongReceivedExecutorNode(const std::string & condition_name, const BT::NodeConfig & conf);
PongReceivedExecutorNode(const std::string & condition_name, const BT::NodeConfiguration & conf);
PongReceivedExecutorNode() = delete;
~PongReceivedExecutorNode();

Expand Down
7 changes: 4 additions & 3 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,16 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>ament_cmake</build_depend>
<build_depend>behaviortree_cpp</build_depend>
<build_depend>behaviortree_cpp_v3</build_depend>
<build_depend>rclcpp</build_depend>
<build_depend>rclcpp_action</build_depend>
<build_depend>rclcpp_lifecycle</build_depend>
<build_depend>rclcpp_components</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>lifecycle_msgs</build_depend>

<exec_depend>behaviortree_cpp</exec_depend>
<build_depend>nav2_msgs</build_depend>

<exec_depend>behaviortree_cpp_v3</exec_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>rclcpp_action</exec_depend>
<exec_depend>rclcpp_lifecycle</exec_depend>
Expand Down
4 changes: 2 additions & 2 deletions src/bt_ros_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include "ros2_behavior_tree_example/plugins/ping_bt_node.hpp"
#include "ros2_behavior_tree_example/plugins/log_status_bt_node.hpp"

#include "behaviortree_cpp/blackboard.h"
#include "behaviortree_cpp_v3/blackboard.h"
#include "rclcpp/publisher.hpp"

#include "std_msgs/msg/string.hpp"
Expand Down Expand Up @@ -124,7 +124,7 @@ namespace bt_ros_example
BtRosNode::timer_callback()
{
RCLCPP_INFO(this->get_logger(), "Ticking the tree");
tree_.tickOnce();
tree_.tickRoot();
return;
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/plugins/log_status_bt_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ namespace polymath
{
namespace bt_ros_example
{
LogStatusNode::LogStatusNode(const std::string & action_name, const BT::NodeConfig & conf)
LogStatusNode::LogStatusNode(const std::string & action_name, const BT::NodeConfiguration & conf)
: BT::SyncActionNode(action_name, conf),
print_ping_pong_(false)
{
Expand Down
2 changes: 1 addition & 1 deletion src/plugins/ping_bt_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ namespace polymath
namespace bt_ros_example
{

PingNode::PingNode(const std::string &action_name, const BT::NodeConfig &conf)
PingNode::PingNode(const std::string &action_name, const BT::NodeConfiguration &conf)
: BT::StatefulActionNode(action_name, conf),
pub_topic_("outgoing_ping")
{
Expand Down
2 changes: 1 addition & 1 deletion src/plugins/pong_received_bt_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ namespace polymath
{
namespace bt_ros_example
{
PongReceivedNode::PongReceivedNode(const std::string & condition_name, const BT::NodeConfig & conf)
PongReceivedNode::PongReceivedNode(const std::string & condition_name, const BT::NodeConfiguration & conf)
: BT::ConditionNode(condition_name, conf),
sub_topic_("incoming_pong"),
pong_id_received_(-1)
Expand Down
2 changes: 1 addition & 1 deletion src/plugins/pong_received_executor_bt_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ namespace polymath
{
namespace bt_ros_example
{
PongReceivedExecutorNode::PongReceivedExecutorNode(const std::string & condition_name, const BT::NodeConfig & conf)
PongReceivedExecutorNode::PongReceivedExecutorNode(const std::string & condition_name, const BT::NodeConfiguration & conf)
: BT::ConditionNode(condition_name, conf),
sub_topic_("incoming_pong"),
pong_id_received_(-1)
Expand Down