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>
32 #include <traffic_simulator_msgs/msg/obstacle.hpp>
33 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
34 #include <unordered_map>
35 #include <vector>
36 
37 namespace entity_behavior
38 {
39 class ActionNode : public BT::ActionNodeBase
40 {
41 public:
42  ActionNode(const std::string & name, const BT::NodeConfiguration & config);
43  ~ActionNode() override = default;
44  auto foundConflictingEntity(const lanelet::Ids & following_lanelets) const -> bool;
46  const lanelet::Ids & route_lanelets,
47  const math::geometry::CatmullRomSplineInterface & spline) const -> std::optional<double>;
49  -> std::optional<std::string>;
50  auto calculateStopDistance(const traffic_simulator_msgs::msg::DynamicConstraints &) const
51  -> double;
53  -> std::optional<double>;
55  const lanelet::Ids & route_lanelets,
56  const std::vector<geometry_msgs::msg::Point> & waypoints) const -> std::optional<double>;
58  const lanelet::Ids & route_lanelets,
59  const math::geometry::CatmullRomSplineInterface & spline) const -> std::optional<double>;
60  auto getRightOfWayEntities() const -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
61  auto getRightOfWayEntities(const lanelet::Ids & following_lanelets) const
62  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
63  auto getYieldStopDistance(const lanelet::Ids & following_lanelets) const -> std::optional<double>;
64  auto getOtherEntityStatus(lanelet::Id lanelet_id) const
65  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
66  auto stopEntity() const -> void;
67  auto getHorizon() const -> double;
68  auto getActionStatus() const noexcept -> traffic_simulator_msgs::msg::ActionStatus;
69  auto getEntityName() const noexcept -> std::string;
70 
72  auto executeTick() -> BT::NodeStatus override;
73 
74  void halt() override final { setStatus(BT::NodeStatus::IDLE); }
75 
76  static BT::PortsList providedPorts()
77  {
78  return {
79  // clang-format off
80  BT::InputPort<double>("current_time"),
81  BT::InputPort<double>("matching_distance_for_lanelet_pose_calculation"),
82  BT::InputPort<double>("step_time"),
83  BT::InputPort<EntityStatusDict>("other_entity_status"),
84  BT::InputPort<lanelet::Ids>("route_lanelets"),
85  BT::InputPort<std::optional<double>>("target_speed"),
86  BT::InputPort<std::shared_ptr<hdmap_utils::HdMapUtils>>("hdmap_utils"),
87  BT::InputPort<std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>>("entity_status"),
88  BT::InputPort<std::shared_ptr<traffic_simulator::TrafficLightManager>>("traffic_light_manager"),
89  BT::InputPort<traffic_simulator::behavior::Request>("request"),
90  BT::OutputPort<std::optional<traffic_simulator_msgs::msg::Obstacle>>("obstacle"),
91  BT::OutputPort<std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>>("updated_status"),
92  BT::OutputPort<traffic_simulator_msgs::msg::WaypointsArray>("waypoints"),
93  BT::OutputPort<traffic_simulator::behavior::Request>("request"),
94  // clang-format on
95  };
96  }
97  auto getBlackBoardValues() -> void;
98  auto getEntityStatus(const std::string & target_name) const
101  const math::geometry::CatmullRomSplineInterface & spline, const std::string target_name,
102  double width_extension_right = 0.0, double width_extension_left = 0.0,
103  double length_extension_front = 0.0, double length_extension_rear = 0.0) const
104  -> std::optional<double>;
106  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
107  -> traffic_simulator::CanonicalizedEntityStatus;
109  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
110  -> traffic_simulator::CanonicalizedEntityStatus;
111 
112 protected:
114  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils;
115  std::shared_ptr<traffic_simulator::TrafficLightManager> traffic_light_manager;
116  std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus> entity_status;
117  double current_time;
118  double step_time;
120  std::optional<double> target_speed;
121  std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus> updated_status;
123  lanelet::Ids route_lanelets;
124 
125 private:
126  auto getDistanceToTargetEntityOnCrosswalk(
127  const math::geometry::CatmullRomSplineInterface & spline,
128  const traffic_simulator::CanonicalizedEntityStatus & status) const -> std::optional<double>;
130  const math::geometry::CatmullRomSplineInterface & spline,
131  const traffic_simulator::CanonicalizedEntityStatus & status, double width_extension_right = 0.0,
132  double width_extension_left = 0.0, double length_extension_front = 0.0,
133  double length_extension_rear = 0.0) const -> std::optional<double>;
134  auto getConflictingEntityStatus(const lanelet::Ids & following_lanelets) const
135  -> std::optional<traffic_simulator::CanonicalizedEntityStatus>;
136  auto getConflictingEntityStatusOnCrossWalk(const lanelet::Ids & route_lanelets) const
137  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
138  auto getConflictingEntityStatusOnLane(const lanelet::Ids & route_lanelets) const
139  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
140 };
141 } // namespace entity_behavior
142 
143 #endif // BEHAVIOR_TREE_PLUGIN__ACTION_NODE_HPP_
Definition: action_node.hpp:40
EntityStatusDict other_entity_status
Definition: action_node.hpp:122
auto getDistanceToTrafficLightStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:191
void halt() override final
Definition: action_node.hpp:74
~ActionNode() override=default
lanelet::Ids route_lanelets
Definition: action_node.hpp:123
auto stopEntity() const -> void
Definition: action_node.cpp:90
auto calculateStopDistance(const traffic_simulator_msgs::msg::DynamicConstraints &) const -> double
Definition: action_node.cpp:517
auto getDistanceToStopLine(const lanelet::Ids &route_lanelets, const std::vector< geometry_msgs::msg::Point > &waypoints) const -> std::optional< double >
Definition: action_node.cpp:219
auto getEntityStatus(const std::string &target_name) const -> traffic_simulator::CanonicalizedEntityStatus
Definition: action_node.cpp:280
std::shared_ptr< traffic_simulator::TrafficLightManager > traffic_light_manager
Definition: action_node.hpp:115
auto getHorizon() const -> double
Definition: action_node.cpp:85
double step_time
Definition: action_node.hpp:118
traffic_simulator::behavior::Request request
Definition: action_node.hpp:113
auto getDistanceToFrontEntity(const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:226
auto getDistanceToTargetEntityPolygon(const math::geometry::CatmullRomSplineInterface &spline, const std::string target_name, double width_extension_right=0.0, double width_extension_left=0.0, double length_extension_front=0.0, double length_extension_rear=0.0) const -> std::optional< double >
Definition: action_node.cpp:289
auto getDistanceToConflictingEntity(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:319
double default_matching_distance_for_lanelet_pose_calculation
Definition: action_node.hpp:119
auto getYieldStopDistance(const lanelet::Ids &following_lanelets) const -> std::optional< double >
Definition: action_node.cpp:111
auto getFrontEntityName(const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< std::string >
Definition: action_node.cpp:236
std::shared_ptr< traffic_simulator::CanonicalizedEntityStatus > entity_status
Definition: action_node.hpp:116
auto getRightOfWayEntities() const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
Definition: action_node.cpp:167
auto getOtherEntityStatus(lanelet::Id lanelet_id) const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
Definition: action_node.cpp:97
auto calculateUpdatedEntityStatus(double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::CanonicalizedEntityStatus
Definition: action_node.cpp:399
double current_time
Definition: action_node.hpp:117
static BT::PortsList providedPorts()
Definition: action_node.hpp:76
auto getEntityName() const noexcept -> std::string
Definition: action_node.cpp:532
ActionNode(const std::string &name, const BT::NodeConfiguration &config)
Definition: action_node.cpp:36
auto executeTick() -> BT::NodeStatus override
throws if the derived class return RUNNING.
Definition: action_node.cpp:41
auto foundConflictingEntity(const lanelet::Ids &following_lanelets) const -> bool
Definition: action_node.cpp:377
auto getActionStatus() const noexcept -> traffic_simulator_msgs::msg::ActionStatus
Definition: action_node.cpp:527
std::shared_ptr< traffic_simulator::CanonicalizedEntityStatus > updated_status
Definition: action_node.hpp:121
std::optional< double > target_speed
Definition: action_node.hpp:120
auto calculateUpdatedEntityStatusInWorldFrame(double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::CanonicalizedEntityStatus
Definition: action_node.cpp:478
auto getBlackBoardValues() -> void
Definition: action_node.cpp:43
Definition: catmull_rom_spline_interface.hpp:30
Definition: entity_status.hpp:29
Definition: action_node.hpp:38
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