scenario_simulator_v2 C++ API
action_node.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__ACTION_NODE_HPP_
16 #define BEHAVIOR_TREE_PLUGIN__ACTION_NODE_HPP_
17 
18 #include <behaviortree_cpp_v3/action_node.h>
19 
20 #include <algorithm>
22 #include <memory>
23 #include <optional>
24 #include <string>
34 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
35 #include <traffic_simulator_msgs/msg/obstacle.hpp>
36 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
37 #include <unordered_map>
38 #include <vector>
39 
40 namespace entity_behavior
41 {
42 BT::PortsList operator+(const BT::PortsList & ports_0, const BT::PortsList & ports_1);
43 
44 class ActionNode : public BT::ActionNodeBase
45 {
46 public:
47  ActionNode(const std::string & name, const BT::NodeConfiguration & config);
48  ~ActionNode() override = default;
50  const lanelet::Ids & route_lanelets,
51  const math::geometry::CatmullRomSplineInterface & spline) const -> std::optional<double>;
53  -> std::optional<std::string>;
54  auto calculateStopDistance(const traffic_simulator_msgs::msg::DynamicConstraints &) const
55  -> double;
57  -> std::optional<double>;
59  const lanelet::Ids & route_lanelets,
60  const math::geometry::CatmullRomSplineInterface & spline) const -> std::optional<double>;
61  auto getRightOfWayEntities() const -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
62  auto getRightOfWayEntities(const lanelet::Ids & following_lanelets) const
63  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
64  auto getYieldStopDistance(const lanelet::Ids & following_lanelets) const -> std::optional<double>;
65  auto stopEntity() const -> void;
66  auto getHorizon() const -> double;
67 
69  auto executeTick() -> BT::NodeStatus override;
70 
71  void halt() override final { setStatus(BT::NodeStatus::IDLE); }
72 
73  static BT::PortsList providedPorts()
74  {
75  return {
76  // clang-format off
77  BT::InputPort<double>("current_time"),
78  BT::InputPort<double>("matching_distance_for_lanelet_pose_calculation"),
79  BT::InputPort<double>("step_time"),
80  BT::InputPort<EntityStatusDict>("other_entity_status"),
81  BT::InputPort<lanelet::Ids>("route_lanelets"),
82  BT::InputPort<std::optional<double>>("target_speed"),
83  BT::InputPort<std::shared_ptr<hdmap_utils::HdMapUtils>>("hdmap_utils"),
84  BT::InputPort<std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>>("canonicalized_entity_status"),
85  BT::InputPort<std::shared_ptr<traffic_simulator::TrafficLightsBase>>("traffic_lights"),
86  BT::InputPort<traffic_simulator::behavior::Request>("request"),
87  BT::InputPort<std::shared_ptr<EuclideanDistancesMap>>("euclidean_distances_map"),
88  BT::InputPort<traffic_simulator_msgs::msg::BehaviorParameter>("behavior_parameter"),
89  BT::OutputPort<std::optional<traffic_simulator_msgs::msg::Obstacle>>("obstacle"),
90  BT::OutputPort<traffic_simulator_msgs::msg::WaypointsArray>("waypoints"),
91  BT::OutputPort<traffic_simulator::behavior::Request>("request"),
92  // clang-format on
93  };
94  }
95 
96  virtual auto getBlackBoardValues() -> void;
97  auto getEntityStatus(const std::string & target_name) const
99 
100  auto setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus & entity_status) -> void;
102  const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
105  const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
107 
108 protected:
110  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils_;
111  std::shared_ptr<traffic_simulator::TrafficLightsBase> traffic_lights_;
112  std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus> canonicalized_entity_status_;
114  double step_time_;
116  std::optional<double> target_speed_;
118  lanelet::Ids route_lanelets_;
119  traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter_;
120 
121  virtual bool checkPreconditions() { return true; }
122  virtual BT::NodeStatus doAction() = 0;
125  const traffic_simulator::CanonicalizedEntityStatus & status) const -> std::optional<double>;
126 
127 private:
128  auto foundConflictingEntity(const lanelet::Ids & following_lanelets) const -> bool;
129  auto getDistanceToTargetEntityOnCrosswalk(
131  const traffic_simulator::CanonicalizedEntityStatus & status) const -> std::optional<double>;
132  auto getConflictingEntityStatusOnCrossWalk(const lanelet::Ids & route_lanelets) const
133  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
134  auto getConflictingEntityStatusOnLane(const lanelet::Ids & route_lanelets) const
135  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
136  auto getOtherEntityStatus(lanelet::Id lanelet_id) const
137  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
138  auto isOtherEntityAtConsideredAltitude(
139  const traffic_simulator::CanonicalizedEntityStatus & entity_status) const -> bool;
140  auto tick() -> BT::NodeStatus override;
141 
142  std::shared_ptr<EuclideanDistancesMap> euclidean_distances_map_;
143 };
144 } // namespace entity_behavior
145 
146 #endif // BEHAVIOR_TREE_PLUGIN__ACTION_NODE_HPP_
Definition: action_node.hpp:45
std::optional< double > target_speed_
Definition: action_node.hpp:116
auto getDistanceToTrafficLightStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:221
void halt() override final
Definition: action_node.hpp:71
~ActionNode() override=default
auto stopEntity() const -> void
Definition: action_node.cpp:118
auto calculateStopDistance(const traffic_simulator_msgs::msg::DynamicConstraints &) const -> double
Definition: action_node.cpp:616
lanelet::Ids route_lanelets_
Definition: action_node.hpp:118
auto calculateUpdatedEntityStatus(const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
Definition: action_node.cpp:490
auto setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus &entity_status) -> void
Definition: action_node.cpp:125
EntityStatusDict other_entity_status_
Definition: action_node.hpp:117
auto getHorizon() const -> double
Definition: action_node.cpp:113
double default_matching_distance_for_lanelet_pose_calculation_
Definition: action_node.hpp:115
virtual BT::NodeStatus doAction()=0
auto getDistanceToFrontEntity(const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:244
std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils_
Definition: action_node.hpp:110
double step_time_
Definition: action_node.hpp:114
virtual bool checkPreconditions()
Definition: action_node.hpp:121
auto getEntityStatus(const std::string &target_name) const -> const traffic_simulator::CanonicalizedEntityStatus &
Definition: action_node.cpp:307
traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter_
Definition: action_node.hpp:119
auto getDistanceToConflictingEntity(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:415
auto getYieldStopDistance(const lanelet::Ids &following_lanelets) const -> std::optional< double >
Definition: action_node.cpp:144
auto calculateUpdatedEntityStatusInWorldFrame(const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
Definition: action_node.cpp:531
auto getFrontEntityName(const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< std::string >
Definition: action_node.cpp:254
auto getRightOfWayEntities() const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
Definition: action_node.cpp:199
std::shared_ptr< traffic_simulator::TrafficLightsBase > traffic_lights_
Definition: action_node.hpp:111
std::shared_ptr< traffic_simulator::CanonicalizedEntityStatus > canonicalized_entity_status_
Definition: action_node.hpp:112
static BT::PortsList providedPorts()
Definition: action_node.hpp:73
ActionNode(const std::string &name, const BT::NodeConfiguration &config)
Definition: action_node.cpp:47
auto executeTick() -> BT::NodeStatus override
throws if the derived class return RUNNING.
Definition: action_node.cpp:52
auto getDistanceToTargetEntity(const math::geometry::CatmullRomSplineInterface &spline, const traffic_simulator::CanonicalizedEntityStatus &status) const -> std::optional< double >
Definition: action_node.cpp:332
double current_time_
Definition: action_node.hpp:113
traffic_simulator::behavior::Request request_
Definition: action_node.hpp:109
virtual auto getBlackBoardValues() -> void
Definition: action_node.cpp:63
Definition: catmull_rom_spline_interface.hpp:30
Definition: entity_status.hpp:32
Definition: action_node.hpp:41
std::unordered_map< std::string, traffic_simulator::CanonicalizedEntityStatus > EntityStatusDict
Definition: behavior_plugin_base.hpp:37
BT::PortsList operator+(const BT::PortsList &ports_0, const BT::PortsList &ports_1)
Definition: action_node.cpp:40
Definition: lanelet_wrapper.hpp:40
Request
Definition: behavior.hpp:25
Definition: api.hpp:32
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:25
std::string string
Definition: junit5.hpp:26