scenario_simulator_v2 C++ API
pedestrian_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__PEDESTRIAN__PEDESTRIAN_ACTION_NODE_HPP_
16 #define BEHAVIOR_TREE_PLUGIN__PEDESTRIAN__PEDESTRIAN_ACTION_NODE_HPP_
17 
18 #include <behaviortree_cpp_v3/action_node.h>
19 
21 #include <memory>
22 #include <string>
23 #include <traffic_simulator_msgs/msg/pedestrian_parameters.hpp>
24 
25 namespace entity_behavior
26 {
28 {
29 public:
30  PedestrianActionNode(const std::string & name, const BT::NodeConfiguration & config);
31  void getBlackBoardValues();
32  static BT::PortsList providedPorts()
33  {
34  BT::PortsList ports = {
35  // clang-format off
36  BT::InputPort<traffic_simulator_msgs::msg::BehaviorParameter>("behavior_parameter"),
37  BT::InputPort<traffic_simulator_msgs::msg::PedestrianParameters>("pedestrian_parameters"),
38  // clang-format on
39  };
40  BT::PortsList parent_ports = entity_behavior::ActionNode::providedPorts();
41  for (const auto & parent_port : parent_ports) {
42  ports.emplace(parent_port.first, parent_port.second);
43  }
44  return ports;
45  }
46  traffic_simulator_msgs::msg::PedestrianParameters pedestrian_parameters;
50 
51 protected:
52  traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter;
53 };
54 } // namespace entity_behavior
55 
56 #endif // BEHAVIOR_TREE_PLUGIN__PEDESTRIAN__PEDESTRIAN_ACTION_NODE_HPP_
Definition: action_node.hpp:41
static BT::PortsList providedPorts()
Definition: action_node.hpp:75
std::optional< double > target_speed
Definition: action_node.hpp:120
Definition: pedestrian_action_node.hpp:28
PedestrianActionNode(const std::string &name, const BT::NodeConfiguration &config)
Definition: pedestrian_action_node.cpp:25
static BT::PortsList providedPorts()
Definition: pedestrian_action_node.hpp:32
traffic_simulator_msgs::msg::PedestrianParameters pedestrian_parameters
Definition: pedestrian_action_node.hpp:46
void getBlackBoardValues()
Definition: pedestrian_action_node.cpp:31
traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter
Definition: pedestrian_action_node.hpp:52
auto calculateUpdatedEntityStatus(double target_speed) const -> traffic_simulator::EntityStatus
Definition: pedestrian_action_node.cpp:44
auto calculateUpdatedEntityStatusInWorldFrame(double target_speed) const -> traffic_simulator::EntityStatus
Definition: pedestrian_action_node.cpp:51
Definition: action_node.hpp:39
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:25
std::string string
Definition: junit5.hpp:26