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/obstacle.hpp>
35 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
36 #include <unordered_map>
37 #include <vector>
38 
39 namespace entity_behavior
40 {
41 BT::PortsList operator+(const BT::PortsList & ports_0, const BT::PortsList & ports_1);
42 
43 class ActionNode : public BT::ActionNodeBase
44 {
45 public:
46  ActionNode(const std::string & name, const BT::NodeConfiguration & config);
47  ~ActionNode() override = default;
48  auto foundConflictingEntity(const lanelet::Ids & following_lanelets) const -> bool;
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 std::vector<geometry_msgs::msg::Point> & waypoints) const -> std::optional<double>;
62  const lanelet::Ids & route_lanelets,
63  const math::geometry::CatmullRomSplineInterface & spline) const -> std::optional<double>;
64  auto getRightOfWayEntities() const -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
65  auto getRightOfWayEntities(const lanelet::Ids & following_lanelets) const
66  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
67  auto getYieldStopDistance(const lanelet::Ids & following_lanelets) const -> std::optional<double>;
68  auto getOtherEntityStatus(lanelet::Id lanelet_id) const
69  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
70  auto stopEntity() const -> void;
71  auto getHorizon() const -> double;
72 
74  auto executeTick() -> BT::NodeStatus override;
75 
76  void halt() override final { setStatus(BT::NodeStatus::IDLE); }
77 
78  static BT::PortsList providedPorts()
79  {
80  return {
81  // clang-format off
82  BT::InputPort<double>("current_time"),
83  BT::InputPort<double>("matching_distance_for_lanelet_pose_calculation"),
84  BT::InputPort<double>("step_time"),
85  BT::InputPort<EntityStatusDict>("other_entity_status"),
86  BT::InputPort<lanelet::Ids>("route_lanelets"),
87  BT::InputPort<std::optional<double>>("target_speed"),
88  BT::InputPort<std::shared_ptr<hdmap_utils::HdMapUtils>>("hdmap_utils"),
89  BT::InputPort<std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>>("canonicalized_entity_status"),
90  BT::InputPort<std::shared_ptr<traffic_simulator::TrafficLightsBase>>("traffic_lights"),
91  BT::InputPort<traffic_simulator::behavior::Request>("request"),
92  BT::OutputPort<std::optional<traffic_simulator_msgs::msg::Obstacle>>("obstacle"),
93  BT::OutputPort<traffic_simulator_msgs::msg::WaypointsArray>("waypoints"),
94  BT::OutputPort<traffic_simulator::behavior::Request>("request"),
95  // clang-format on
96  };
97  }
98 
99  virtual auto getBlackBoardValues() -> void;
100  auto getEntityStatus(const std::string & target_name) const
102 
103  auto setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus & entity_status) -> void;
105  const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
108  const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
110 
111 protected:
113  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils;
114  std::shared_ptr<traffic_simulator::TrafficLightsBase> traffic_lights;
115  std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus> canonicalized_entity_status;
116  double current_time;
117  double step_time;
119  std::optional<double> target_speed;
121  lanelet::Ids route_lanelets;
122 
125  const traffic_simulator::CanonicalizedEntityStatus & status) const -> std::optional<double>;
126 
127 private:
128  auto getDistanceToTargetEntityOnCrosswalk(
130  const traffic_simulator::CanonicalizedEntityStatus & status) const -> std::optional<double>;
131  auto getConflictingEntityStatus(const lanelet::Ids & following_lanelets) const
132  -> std::optional<traffic_simulator::CanonicalizedEntityStatus>;
133  auto getConflictingEntityStatusOnCrossWalk(const lanelet::Ids & route_lanelets) const
134  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
135  auto getConflictingEntityStatusOnLane(const lanelet::Ids & route_lanelets) const
136  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
137  auto isOtherEntityAtConsideredAltitude(
138  const traffic_simulator::CanonicalizedEntityStatus & entity_status) const -> bool;
139 };
140 } // namespace entity_behavior
141 
142 #endif // BEHAVIOR_TREE_PLUGIN__ACTION_NODE_HPP_
Definition: action_node.hpp:44
EntityStatusDict other_entity_status
Definition: action_node.hpp:120
auto getDistanceToTrafficLightStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:204
void halt() override final
Definition: action_node.hpp:76
~ActionNode() override=default
lanelet::Ids route_lanelets
Definition: action_node.hpp:121
std::shared_ptr< traffic_simulator::CanonicalizedEntityStatus > canonicalized_entity_status
Definition: action_node.hpp:115
auto stopEntity() const -> void
Definition: action_node.cpp:101
auto calculateStopDistance(const traffic_simulator_msgs::msg::DynamicConstraints &) const -> double
Definition: action_node.cpp:588
auto getDistanceToStopLine(const lanelet::Ids &route_lanelets, const std::vector< geometry_msgs::msg::Point > &waypoints) const -> std::optional< double >
Definition: action_node.cpp:227
auto calculateUpdatedEntityStatus(const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
Definition: action_node.cpp:462
auto setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus &entity_status) -> void
Definition: action_node.cpp:108
auto getHorizon() const -> double
Definition: action_node.cpp:96
std::shared_ptr< traffic_simulator::TrafficLightsBase > traffic_lights
Definition: action_node.hpp:114
double step_time
Definition: action_node.hpp:117
traffic_simulator::behavior::Request request
Definition: action_node.hpp:112
auto getDistanceToFrontEntity(const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:234
auto getEntityStatus(const std::string &target_name) const -> const traffic_simulator::CanonicalizedEntityStatus &
Definition: action_node.cpp:288
std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils
Definition: action_node.hpp:113
auto getDistanceToConflictingEntity(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:387
double default_matching_distance_for_lanelet_pose_calculation
Definition: action_node.hpp:118
auto getYieldStopDistance(const lanelet::Ids &following_lanelets) const -> std::optional< double >
Definition: action_node.cpp:127
auto calculateUpdatedEntityStatusInWorldFrame(const double local_target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
Definition: action_node.cpp:503
auto getFrontEntityName(const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< std::string >
Definition: action_node.cpp:244
auto getRightOfWayEntities() const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
Definition: action_node.cpp:182
auto getOtherEntityStatus(lanelet::Id lanelet_id) const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
Definition: action_node.cpp:115
double current_time
Definition: action_node.hpp:116
static BT::PortsList providedPorts()
Definition: action_node.hpp:78
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 foundConflictingEntity(const lanelet::Ids &following_lanelets) const -> bool
Definition: action_node.cpp:442
auto getDistanceToTargetEntity(const math::geometry::CatmullRomSplineInterface &spline, const traffic_simulator::CanonicalizedEntityStatus &status) const -> std::optional< double >
Definition: action_node.cpp:313
std::optional< double > target_speed
Definition: action_node.hpp:119
virtual auto getBlackBoardValues() -> void
Definition: action_node.cpp:54
Definition: catmull_rom_spline_interface.hpp:30
Definition: entity_status.hpp:32
Definition: action_node.hpp:40
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:39
Request
Definition: behavior.hpp:25
Definition: api.hpp:48
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:25
std::string string
Definition: junit5.hpp:26