scenario_simulator_v2 C++ API
behavior_tree.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef BEHAVIOR_TREE_PLUGIN__PEDESTRIAN__BEHAVIOR_TREE_HPP_
16 #define BEHAVIOR_TREE_PLUGIN__PEDESTRIAN__BEHAVIOR_TREE_HPP_
17 
18 #include <behaviortree_cpp_v3/bt_factory.h>
19 #include <behaviortree_cpp_v3/loggers/bt_cout_logger.h>
20 
24 #include <functional>
25 #include <geometry_msgs/msg/point.hpp>
26 #include <map>
27 #include <memory>
28 #include <optional>
29 #include <string>
32 #include <traffic_simulator_msgs/msg/entity_status.hpp>
33 #include <vector>
34 #include <visualization_msgs/msg/marker_array.hpp>
35 
36 namespace entity_behavior
37 {
39 {
40 public:
41  void configure(const rclcpp::Logger & logger) override;
42  auto update(const double current_time, const double step_time) -> void override;
43  const std::string & getCurrentAction() const override;
44 
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 \
48  { \
49  tree_.rootBlackboard()->set<TYPE>(get##NAME##Key(), value); \
50  }
51 
52  // clang-format off
53  DEFINE_GETTER_SETTER(BehaviorParameter, traffic_simulator_msgs::msg::BehaviorParameter)
54  DEFINE_GETTER_SETTER(CanonicalizedEntityStatus, std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>)
55  DEFINE_GETTER_SETTER(CurrentTime, double)
56  DEFINE_GETTER_SETTER(DebugMarker, std::vector<visualization_msgs::msg::Marker>)
57  DEFINE_GETTER_SETTER(DefaultMatchingDistanceForLaneletPoseCalculation, double)
58  DEFINE_GETTER_SETTER(GoalPoses, std::vector<geometry_msgs::msg::Pose>)
59  DEFINE_GETTER_SETTER(HdMapUtils, std::shared_ptr<hdmap_utils::HdMapUtils>)
60  DEFINE_GETTER_SETTER(LaneChangeParameters, traffic_simulator::lane_change::Parameter)
61  DEFINE_GETTER_SETTER(Obstacle, std::optional<traffic_simulator_msgs::msg::Obstacle>)
63  DEFINE_GETTER_SETTER(PedestrianParameters, traffic_simulator_msgs::msg::PedestrianParameters)
64  DEFINE_GETTER_SETTER(PolylineTrajectory, std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory>)
65  DEFINE_GETTER_SETTER(ReferenceTrajectory, std::shared_ptr<math::geometry::CatmullRomSpline>)
67  DEFINE_GETTER_SETTER(RouteLanelets, lanelet::Ids)
68  DEFINE_GETTER_SETTER(StepTime, double)
69  DEFINE_GETTER_SETTER(TargetSpeed, std::optional<double>)
70  DEFINE_GETTER_SETTER(TrafficLightManager, std::shared_ptr<traffic_simulator::TrafficLightManager>)
71  DEFINE_GETTER_SETTER(VehicleParameters, traffic_simulator_msgs::msg::VehicleParameters)
72  DEFINE_GETTER_SETTER(Waypoints, traffic_simulator_msgs::msg::WaypointsArray)
73  // clang-format on
74 
75 #undef DEFINE_GETTER_SETTER
76 
77 private:
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_;
81  BT::Tree tree_;
82  std::unique_ptr<behavior_tree_plugin::LoggingEvent> logging_event_ptr_;
83  std::unique_ptr<behavior_tree_plugin::ResetRequestEvent> reset_request_event_ptr_;
84 };
85 } // namespace entity_behavior
86 
87 #endif // BEHAVIOR_TREE_PLUGIN__PEDESTRIAN__BEHAVIOR_TREE_HPP_
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: cache.hpp:46
Definition: bounding_box.hpp:32
Definition: cache.hpp:27
Request
Definition: behavior.hpp:25
Definition: api.hpp:48
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