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>
33 #include <traffic_simulator_msgs/msg/obstacle.hpp>
34 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
35 #include <unordered_map>
36 #include <vector>
37 
38 namespace entity_behavior
39 {
40 class ActionNode : public BT::ActionNodeBase
41 {
42 public:
43  ActionNode(const std::string & name, const BT::NodeConfiguration & config);
44  ~ActionNode() override = default;
45  auto foundConflictingEntity(const lanelet::Ids & following_lanelets) const -> bool;
47  const lanelet::Ids & route_lanelets,
48  const math::geometry::CatmullRomSplineInterface & spline) const -> std::optional<double>;
50  -> std::optional<std::string>;
51  auto calculateStopDistance(const traffic_simulator_msgs::msg::DynamicConstraints &) const
52  -> double;
54  -> std::optional<double>;
56  const lanelet::Ids & route_lanelets,
57  const std::vector<geometry_msgs::msg::Point> & waypoints) const -> 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 getOtherEntityStatus(lanelet::Id lanelet_id) const
66  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
67  auto stopEntity() const -> void;
68  auto getHorizon() const -> double;
69 
71  auto executeTick() -> BT::NodeStatus override;
72 
73  void halt() override final { setStatus(BT::NodeStatus::IDLE); }
74 
75  static BT::PortsList providedPorts()
76  {
77  return {
78  // clang-format off
79  BT::InputPort<double>("current_time"),
80  BT::InputPort<double>("matching_distance_for_lanelet_pose_calculation"),
81  BT::InputPort<double>("step_time"),
82  BT::InputPort<EntityStatusDict>("other_entity_status"),
83  BT::InputPort<lanelet::Ids>("route_lanelets"),
84  BT::InputPort<std::optional<double>>("target_speed"),
85  BT::InputPort<std::shared_ptr<hdmap_utils::HdMapUtils>>("hdmap_utils"),
86  BT::InputPort<std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus>>("canonicalized_entity_status"),
87  BT::InputPort<std::shared_ptr<traffic_simulator::TrafficLightsBase>>("traffic_lights"),
88  BT::InputPort<traffic_simulator::behavior::Request>("request"),
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  auto getBlackBoardValues() -> void;
96  auto getEntityStatus(const std::string & target_name) const
99  const math::geometry::CatmullRomSplineInterface & spline, const std::string target_name,
100  double width_extension_right = 0.0, double width_extension_left = 0.0,
101  double length_extension_front = 0.0, double length_extension_rear = 0.0) const
102  -> std::optional<double>;
103 
104  auto setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus & entity_status) -> void;
106  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
109  double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const
111 
112 protected:
114  std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils;
115  std::shared_ptr<traffic_simulator::TrafficLightsBase> traffic_lights;
116  std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus> canonicalized_entity_status;
117  double current_time;
118  double step_time;
120  std::optional<double> target_speed;
122  lanelet::Ids route_lanelets;
123 
124 private:
125  auto getDistanceToTargetEntityOnCrosswalk(
126  const math::geometry::CatmullRomSplineInterface & spline,
127  const traffic_simulator::CanonicalizedEntityStatus & status) const -> std::optional<double>;
129  const math::geometry::CatmullRomSplineInterface & spline,
130  const traffic_simulator::CanonicalizedEntityStatus & status, double width_extension_right = 0.0,
131  double width_extension_left = 0.0, double length_extension_front = 0.0,
132  double length_extension_rear = 0.0) const -> std::optional<double>;
133  auto getConflictingEntityStatus(const lanelet::Ids & following_lanelets) const
134  -> std::optional<traffic_simulator::CanonicalizedEntityStatus>;
135  auto getConflictingEntityStatusOnCrossWalk(const lanelet::Ids & route_lanelets) const
136  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
137  auto getConflictingEntityStatusOnLane(const lanelet::Ids & route_lanelets) const
138  -> std::vector<traffic_simulator::CanonicalizedEntityStatus>;
139 };
140 } // namespace entity_behavior
141 
142 #endif // BEHAVIOR_TREE_PLUGIN__ACTION_NODE_HPP_
Definition: action_node.hpp:41
EntityStatusDict other_entity_status
Definition: action_node.hpp:121
auto getDistanceToTrafficLightStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:198
void halt() override final
Definition: action_node.hpp:73
~ActionNode() override=default
lanelet::Ids route_lanelets
Definition: action_node.hpp:122
std::shared_ptr< traffic_simulator::CanonicalizedEntityStatus > canonicalized_entity_status
Definition: action_node.hpp:116
auto stopEntity() const -> void
Definition: action_node.cpp:90
auto calculateStopDistance(const traffic_simulator_msgs::msg::DynamicConstraints &) const -> double
Definition: action_node.cpp:536
auto getDistanceToStopLine(const lanelet::Ids &route_lanelets, const std::vector< geometry_msgs::msg::Point > &waypoints) const -> std::optional< double >
Definition: action_node.cpp:221
auto setCanonicalizedEntityStatus(const traffic_simulator::EntityStatus &entity_status) -> void
Definition: action_node.cpp:97
auto calculateUpdatedEntityStatus(double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
Definition: action_node.cpp:402
auto getHorizon() const -> double
Definition: action_node.cpp:85
std::shared_ptr< traffic_simulator::TrafficLightsBase > traffic_lights
Definition: action_node.hpp:115
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:228
auto calculateUpdatedEntityStatusInWorldFrame(double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &) const -> traffic_simulator::EntityStatus
Definition: action_node.cpp:495
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:292
auto getEntityStatus(const std::string &target_name) const -> const traffic_simulator::CanonicalizedEntityStatus &
Definition: action_node.cpp:282
auto getDistanceToConflictingEntity(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: action_node.cpp:322
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:118
auto getFrontEntityName(const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< std::string >
Definition: action_node.cpp:238
auto getRightOfWayEntities() const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
Definition: action_node.cpp:174
auto getOtherEntityStatus(lanelet::Id lanelet_id) const -> std::vector< traffic_simulator::CanonicalizedEntityStatus >
Definition: action_node.cpp:104
double current_time
Definition: action_node.hpp:117
static BT::PortsList providedPorts()
Definition: action_node.hpp:75
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:380
std::optional< double > target_speed
Definition: action_node.hpp:120
auto getBlackBoardValues() -> void
Definition: action_node.cpp:43
Definition: catmull_rom_spline_interface.hpp:30
Definition: entity_status.hpp:32
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:49
std::string string
Definition: junit5.hpp:26
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32