15 #ifndef BEHAVIOR_TREE_PLUGIN__PEDESTRIAN__BEHAVIOR_TREE_HPP_
16 #define BEHAVIOR_TREE_PLUGIN__PEDESTRIAN__BEHAVIOR_TREE_HPP_
18 #include <behaviortree_cpp_v3/bt_factory.h>
19 #include <behaviortree_cpp_v3/loggers/bt_cout_logger.h>
25 #include <geometry_msgs/msg/point.hpp>
32 #include <traffic_simulator_msgs/msg/entity_status.hpp>
34 #include <visualization_msgs/msg/marker_array.hpp>
41 void configure(
const rclcpp::Logger & logger)
override;
42 auto update(
const double current_time,
const double step_time) ->
void override;
45 #define DEFINE_GETTER_SETTER(NAME, TYPE) \
46 TYPE get##NAME() override { return tree_.rootBlackboard()->get<TYPE>(get##NAME##Key()); } \
47 void set##NAME(const TYPE & value) override \
49 tree_.rootBlackboard()->set<TYPE>(get##NAME##Key(), value); \
75 #undef DEFINE_GETTER_SETTER
78 auto tickOnce(
const double current_time,
const double step_time) -> BT::NodeStatus;
79 auto createBehaviorTree(
const std::string & format_path) -> BT::Tree;
80 BT::BehaviorTreeFactory factory_;
82 std::unique_ptr<behavior_tree_plugin::LoggingEvent> logging_event_ptr_;
83 std::unique_ptr<behavior_tree_plugin::ResetRequestEvent> reset_request_event_ptr_;
Definition: behavior_plugin_base.hpp:40
Definition: behavior_tree.hpp:39
auto update(const double current_time, const double step_time) -> void override
Definition: behavior_tree.cpp:86
void configure(const rclcpp::Logger &logger) override
Definition: behavior_tree.cpp:27
const std::string & getCurrentAction() const override
Definition: behavior_tree.cpp:81
Definition: action_node.hpp:39
std::unordered_map< std::string, traffic_simulator::CanonicalizedEntityStatus > EntityStatusDict
Definition: behavior_plugin_base.hpp:37
Definition: bounding_box.hpp:32
Request
Definition: behavior.hpp:25
std::string string
Definition: junit5.hpp:26
#define DEFINE_GETTER_SETTER(NAME, TYPE)
Definition: behavior_tree.hpp:45
class definition for the walk straight action