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 <geometry_msgs/msg/point.hpp>
23 #include <memory>
24 #include <optional>
25 #include <string>
35 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
36 #include <traffic_simulator_msgs/msg/obstacle.hpp>
37 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
38 #include <unordered_map>
39 #include <utility>
40 #include <vector>
41 
42 namespace entity_behavior
43 {
44 BT::PortsList operator+(const BT::PortsList & ports_0, const BT::PortsList & ports_1);
45 
46 class ActionNode : public BT::ActionNodeBase
47 {
48 public:
49  ActionNode(const std::string & name, const BT::NodeConfiguration & config);
50  ~ActionNode() override = default;
52  const lanelet::Ids & route_lanelets,
53  const math::geometry::CatmullRomSplineInterface & spline) const -> std::optional<double>;
55  -> std::optional<std::string>;
56  auto calculateStopDistance(const traffic_simulator_msgs::msg::DynamicConstraints &) const
57  -> double;
59  -> std::optional<double>;
61  const std::vector<geometry_msgs::msg::Point> & waypoints, const double width,
62  const std::size_t num_segments) const -> std::optional<std::pair<std::string, double>>;
64  const lanelet::Ids & route_lanelets,
65  const math::geometry::CatmullRomSplineInterface & spline) const -> std::optional<double>;
66  auto getRightOfWayEntities() const -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
67  auto getRightOfWayEntities(const lanelet::Ids & following_lanelets) const
68  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
69  auto getYieldStopDistance(const lanelet::Ids & following_lanelets) const -> std::optional<double>;
70  auto stopEntity() const -> void;
71  auto getHorizon() const -> double;
75  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
76 
78  auto executeTick() -> BT::NodeStatus override;
79 
80  void halt() override final { setStatus(BT::NodeStatus::IDLE); }
81 
82  static BT::PortsList providedPorts()
83  {
84  return {
85  // clang-format off
86  BT::InputPort<double>("current_time"),
87  BT::InputPort<double>("matching_distance_for_lanelet_pose_calculation"),
88  BT::InputPort<double>("step_time"),
89  BT::InputPort<EntityStatusDict>("other_entity_status"),
90  BT::InputPort<lanelet::Ids>("route_lanelets"),
91  BT::InputPort<std::optional<double>>("target_speed"),
92  BT::InputPort<std::shared_ptr<hdmap_utils::HdMapUtils>>("hdmap_utils"),
93  BT::InputPort<std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>>("canonicalized_entity_status"),
94  BT::InputPort<std::shared_ptr<traffic_simulator::TrafficLightsBase>>("traffic_lights"),
95  BT::InputPort<traffic_simulator::behavior::Request>("request"),
96  BT::InputPort<std::shared_ptr<EuclideanDistancesMap>>("euclidean_distances_map"),
97  BT::InputPort<traffic_simulator_msgs::msg::BehaviorParameter>("behavior_parameter"),
98  BT::InputPort<std::optional<double>>("lateral_collision_threshold"),
99  BT::OutputPort<std::optional<traffic_simulator_msgs::msg::Obstacle>>("obstacle"),
100  BT::OutputPort<traffic_simulator_msgs::msg::WaypointsArray>("waypoints"),
101  BT::OutputPort<traffic_simulator::behavior::Request>("request"),
102  // clang-format on
103  };
104  }
105 
106  virtual auto getBlackBoardValues() -> void;
107  auto getEntityStatus(const std::string & target_name) const
109 
110  auto setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus & entity_status) -> void;
112  const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
115  const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
117 
118 protected:
120  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils_;
121  std::shared_ptr<traffic_simulator::TrafficLightsBase> traffic_lights_;
122  std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus> canonicalized_entity_status_;
124  double step_time_;
126  std::optional<double> target_speed_;
128  lanelet::Ids route_lanelets_;
129  traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter_;
130  std::optional<double> lateral_collision_threshold_;
131 
132  virtual bool checkPreconditions() { return true; }
133  virtual BT::NodeStatus doAction() = 0;
134 
135 private:
136  auto foundConflictingEntity(const lanelet::Ids & following_lanelets) const -> bool;
137  auto getDistanceToTargetEntityOnCrosswalk(
139  const traffic_simulator::CanonicalizedEntityStatus & status) const -> std::optional<double>;
140  auto getConflictingEntityStatusOnCrossWalk(const lanelet::Ids & route_lanelets) const
141  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
142  auto getConflictingEntityStatusOnLane(const lanelet::Ids & route_lanelets) const
143  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
144  auto isOtherEntityAtConsideredAltitude(
145  const traffic_simulator::CanonicalizedEntityStatus & entity_status) const -> bool;
146  auto tick() -> BT::NodeStatus override;
147 
148  std::shared_ptr<EuclideanDistancesMap> euclidean_distances_map_;
149 };
150 } // namespace entity_behavior
151 
152 #endif // BEHAVIOR_TREE_PLUGIN__ACTION_NODE_HPP_
Definition: action_node.hpp:47
auto getFrontEntityNameAndDistanceByTrajectory(const std::vector< geometry_msgs::msg::Point > &waypoints, const double width, const std::size_t num_segments) const -> std::optional< std::pair< std::string, double >>
Definition: action_node.cpp:478
std::optional< double > target_speed_
Definition: action_node.hpp:126
auto getDistanceToTrafficLightStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:226
void halt() override final
Definition: action_node.hpp:80
~ActionNode() override=default
auto stopEntity() const -> void
Definition: action_node.cpp:148
auto calculateStopDistance(const traffic_simulator_msgs::msg::DynamicConstraints &) const -> double
Definition: action_node.cpp:718
auto getOtherEntitiesCanonicalizedLaneletPoses() const -> std::vector< traffic_simulator::CanonicalizedLaneletPose >
Definition: action_node.cpp:120
std::optional< double > lateral_collision_threshold_
Definition: action_node.hpp:130
lanelet::Ids route_lanelets_
Definition: action_node.hpp:128
auto calculateUpdatedEntityStatus(const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
Definition: action_node.cpp:592
auto setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus &entity_status) -> void
Definition: action_node.cpp:155
EntityStatusDict other_entity_status_
Definition: action_node.hpp:127
auto getHorizon() const -> double
Definition: action_node.cpp:143
double default_matching_distance_for_lanelet_pose_calculation_
Definition: action_node.hpp:125
virtual BT::NodeStatus doAction()=0
auto getDistanceToFrontEntity(const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:249
std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils_
Definition: action_node.hpp:120
double step_time_
Definition: action_node.hpp:124
virtual bool checkPreconditions()
Definition: action_node.hpp:132
auto getEntityStatus(const std::string &target_name) const -> const traffic_simulator::CanonicalizedEntityStatus &
Definition: action_node.cpp:350
traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter_
Definition: action_node.hpp:129
auto getDistanceToConflictingEntity(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:508
auto getYieldStopDistance(const lanelet::Ids &following_lanelets) const -> std::optional< double >
Definition: action_node.cpp:162
auto getOtherEntitiesCanonicalizedEntityStatuses() const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
Definition: action_node.cpp:132
auto calculateUpdatedEntityStatusInWorldFrame(const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
Definition: action_node.cpp:633
auto getFrontEntityName(const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< std::string >
Definition: action_node.cpp:270
auto getRightOfWayEntities() const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
Definition: action_node.cpp:204
std::shared_ptr< traffic_simulator::TrafficLightsBase > traffic_lights_
Definition: action_node.hpp:121
std::shared_ptr< traffic_simulator::CanonicalizedEntityStatus > canonicalized_entity_status_
Definition: action_node.hpp:122
static BT::PortsList providedPorts()
Definition: action_node.hpp:82
ActionNode(const std::string &name, const BT::NodeConfiguration &config)
Definition: action_node.cpp:50
auto executeTick() -> BT::NodeStatus override
throws if the derived class return RUNNING.
Definition: action_node.cpp:55
double current_time_
Definition: action_node.hpp:123
traffic_simulator::behavior::Request request_
Definition: action_node.hpp:119
virtual auto getBlackBoardValues() -> void
Definition: action_node.cpp:66
Definition: catmull_rom_spline_interface.hpp:30
Definition: entity_status.hpp:32
Definition: action_node.hpp:43
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:43
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