15 #ifndef TRAFFIC_SIMULATOR__ENTITY__PEDESTRIAN_ENTITY_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__PEDESTRIAN_ENTITY_HPP_
20 #include <pluginlib/class_loader.hpp>
21 #include <pugixml.hpp>
26 #include <traffic_simulator_msgs/msg/pedestrian_parameters.hpp>
40 static const std::string name =
"behavior_tree_plugin/PedestrianBehaviorTree";
46 static const std::string name =
"context_gamma_planner/PedestrianPlugin";
61 const traffic_simulator_msgs::msg::PedestrianParameters &,
66 void appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array)
override;
70 auto
onUpdate(const
double current_time, const
double step_time) ->
void override;
76 const geometry_msgs::msg::
Pose & map_pose, const
RouteOption &) override;
134 traffic_simulator::RoutingGraphType::VEHICLE_WITH_ROAD_SHOULDER};
Definition: route_planner.hpp:26
Definition: traffic_lights_base.hpp:44
Definition: entity_base.hpp:52
const std::string name
Definition: entity_base.hpp:348
Definition: pedestrian_entity.hpp:34
void requestWalkStraight() override
Definition: pedestrian_entity.cpp:169
auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
Definition: pedestrian_entity.cpp:114
void requestAcquirePosition(const CanonicalizedLaneletPose &lanelet_pose, const RouteOption &) override
Definition: pedestrian_entity.cpp:174
void requestAssignRoute(const std::vector< CanonicalizedLaneletPose > &waypoints, const RouteOption &) override
Definition: pedestrian_entity.cpp:52
auto getGoalPoses() -> std::vector< geometry_msgs::msg::Pose > override
Definition: pedestrian_entity.cpp:145
~PedestrianEntity() override=default
auto getEntityTypename() const -> const std::string &override
Definition: pedestrian_entity.cpp:204
auto getMaxAcceleration() const -> double override
Definition: pedestrian_entity.cpp:235
auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override
Definition: pedestrian_entity.cpp:154
void setAccelerationRateLimit(double acceleration_rate) override
Definition: pedestrian_entity.cpp:265
auto requestFollowTrajectory(const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void override
Definition: pedestrian_entity.cpp:83
void setDecelerationRateLimit(double deceleration) override
Definition: pedestrian_entity.cpp:285
const traffic_simulator_msgs::msg::PedestrianParameters pedestrian_parameters
Definition: pedestrian_entity.hpp:128
void setTrafficLights(const std::shared_ptr< traffic_simulator::TrafficLightsBase > &ptr) override
Definition: pedestrian_entity.cpp:210
auto getMaxDeceleration() const -> double override
Definition: pedestrian_entity.cpp:240
void setAccelerationLimit(double acceleration) override
Definition: pedestrian_entity.cpp:255
void setVelocityLimit(double linear_velocity) override
Definition: pedestrian_entity.cpp:245
std::string getCurrentAction() const override
Definition: pedestrian_entity.cpp:109
auto getParameters() const -> const traffic_simulator_msgs::msg::PedestrianParameters &
Definition: pedestrian_entity.cpp:217
auto getObstacle() -> std::optional< traffic_simulator_msgs::msg::Obstacle > override
Definition: pedestrian_entity.cpp:140
auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter
Definition: pedestrian_entity.cpp:223
void appendDebugMarker(visualization_msgs::msg::MarkerArray &marker_array) override
Definition: pedestrian_entity.cpp:46
const std::string plugin_name
Definition: pedestrian_entity.hpp:126
auto onUpdate(const double current_time, const double step_time) -> void override
Definition: pedestrian_entity.cpp:295
void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &)
Definition: pedestrian_entity.cpp:229
auto getRouteLanelets(double horizon=100) -> lanelet::Ids override
Definition: pedestrian_entity.cpp:125
PedestrianEntity(const std::string &name, const CanonicalizedEntityStatus &, const traffic_simulator_msgs::msg::PedestrianParameters &, const std::string &plugin_name=BuiltinBehavior::defaultBehavior())
Definition: pedestrian_entity.cpp:27
void cancelRequest() override
Definition: pedestrian_entity.cpp:198
void setDecelerationLimit(double deceleration) override
Definition: pedestrian_entity.cpp:275
Definition: entity_status.hpp:31
Definition: lanelet_pose.hpp:35
Definition: action_node.hpp:41
Definition: lanelet_wrapper.hpp:43
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
Definition: operators.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: pedestrian_entity.hpp:37
static auto behaviorTree() noexcept -> const std::string &
Definition: pedestrian_entity.hpp:38
static auto doNothing() noexcept -> const std::string &
Definition: pedestrian_entity.hpp:50
static auto defaultBehavior() noexcept -> const std::string &
Definition: pedestrian_entity.hpp:56
static auto contextGamma() noexcept -> const std::string &
Definition: pedestrian_entity.hpp:44
Definition: route_option.hpp:25