scenario_simulator_v2 C++ API
stop_at_stop_line_action.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__VEHICLE__FOLLOW_LANE_SEQUENCE__STOP_AT_STOP_LINE_ACTION_HPP_
16 #define BEHAVIOR_TREE_PLUGIN__VEHICLE__FOLLOW_LANE_SEQUENCE__STOP_AT_STOP_LINE_ACTION_HPP_
17 
19 #include <optional>
20 #include <string>
22 #include <vector>
23 
24 namespace entity_behavior
25 {
26 namespace vehicle
27 {
28 namespace follow_lane_sequence
29 {
31 {
32 public:
33  StopAtStopLineAction(const std::string & name, const BT::NodeConfiguration & config);
34  BT::NodeStatus tick() override;
35  static BT::PortsList providedPorts()
36  {
37  BT::PortsList ports = {};
38  BT::PortsList parent_ports = entity_behavior::VehicleActionNode::providedPorts();
39  for (const auto & parent_port : parent_ports) {
40  ports.emplace(parent_port.first, parent_port.second);
41  }
42  return ports;
43  }
44  std::optional<double> calculateTargetSpeed(double current_velocity);
45  const traffic_simulator_msgs::msg::WaypointsArray calculateWaypoints() override;
46  const std::optional<traffic_simulator_msgs::msg::Obstacle> calculateObstacle(
47  const traffic_simulator_msgs::msg::WaypointsArray & waypoints) override;
48 
49 private:
50  bool stopped_;
51  std::optional<double> distance_to_stopline_;
52 };
53 } // namespace follow_lane_sequence
54 } // namespace vehicle
55 } // namespace entity_behavior
56 
57 #endif // BEHAVIOR_TREE_PLUGIN__VEHICLE__FOLLOW_LANE_SEQUENCE__STOP_AT_STOP_LINE_ACTION_HPP_
Definition: vehicle_action_node.hpp:36
static BT::PortsList providedPorts()
Definition: vehicle_action_node.hpp:41
StopAtStopLineAction(const std::string &name, const BT::NodeConfiguration &config)
Definition: stop_at_stop_line_action.cpp:29
std::optional< double > calculateTargetSpeed(double current_velocity)
Definition: stop_at_stop_line_action.cpp:73
const traffic_simulator_msgs::msg::WaypointsArray calculateWaypoints() override
Definition: stop_at_stop_line_action.cpp:54
const std::optional< traffic_simulator_msgs::msg::Obstacle > calculateObstacle(const traffic_simulator_msgs::msg::WaypointsArray &waypoints) override
Definition: stop_at_stop_line_action.cpp:36
static BT::PortsList providedPorts()
Definition: stop_at_stop_line_action.hpp:35
BT::NodeStatus tick() override
Definition: stop_at_stop_line_action.cpp:89
Definition: action_node.hpp:39
std::string string
Definition: junit5.hpp:26