15 #ifndef BEHAVIOR_TREE_PLUGIN__PEDESTRIAN__PEDESTRIAN_ACTION_NODE_HPP_ 
   16 #define BEHAVIOR_TREE_PLUGIN__PEDESTRIAN__PEDESTRIAN_ACTION_NODE_HPP_ 
   18 #include <behaviortree_cpp_v3/action_node.h> 
   23 #include <traffic_simulator_msgs/msg/pedestrian_parameters.hpp> 
   36     return BT::PortsList({
 
   37       BT::InputPort<traffic_simulator_msgs::msg::PedestrianParameters>(
"pedestrian_parameters"),
 
Definition: action_node.hpp:47
static BT::PortsList providedPorts()
Definition: action_node.hpp:78
Definition: pedestrian_action_node.hpp:29
PedestrianActionNode(const std::string &name, const BT::NodeConfiguration &config)
Definition: pedestrian_action_node.cpp:24
static BT::PortsList providedPorts()
Definition: pedestrian_action_node.hpp:33
void getBlackBoardValues() override
Definition: pedestrian_action_node.cpp:30
traffic_simulator_msgs::msg::PedestrianParameters pedestrian_parameters
Definition: pedestrian_action_node.hpp:41
SeeAroundMode should_respect_see_around
Definition: pedestrian_action_node.hpp:47
auto calculateUpdatedEntityStatus(double target_speed) const -> traffic_simulator::EntityStatus
Definition: pedestrian_action_node.cpp:52
auto calculateUpdatedEntityStatusInWorldFrame(double target_speed) const -> traffic_simulator::EntityStatus
Definition: pedestrian_action_node.cpp:59
Definition: action_node.hpp:43
SeeAroundMode
Definition: pedestrian_action_node.hpp:27
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:25
std::string string
Definition: junit5.hpp:26