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 std::shared_ptr<hdmap_utils::HdMapUtils> &,
62 const traffic_simulator_msgs::msg::PedestrianParameters &,
67 void appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array)
override;
69 auto getEntityType() const -> const traffic_simulator_msgs::msg::EntityType & override;
73 void onUpdate(
double current_time,
double step_time) override;
109 const
std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> &) ->
void override;
114 -> const traffic_simulator_msgs::msg::DynamicConstraints & override;
118 auto
getObstacle() ->
std::optional<traffic_simulator_msgs::msg::Obstacle> override;
122 auto
getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override;
Definition: route_planner.hpp:27
Definition: traffic_light_manager.hpp:34
Definition: entity_base.hpp:51
const std::string name
Definition: entity_base.hpp:242
Definition: pedestrian_entity.hpp:34
void requestWalkStraight() override
Definition: pedestrian_entity.cpp:132
auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
Definition: pedestrian_entity.cpp:96
void onUpdate(double current_time, double step_time) override
Definition: pedestrian_entity.cpp:260
~PedestrianEntity() override=default
void requestAssignRoute(const std::vector< CanonicalizedLaneletPose > &waypoints) override
Definition: pedestrian_entity.cpp:53
auto getEntityTypename() const -> const std::string &override
Definition: pedestrian_entity.cpp:170
auto getMaxAcceleration() const -> double override
Definition: pedestrian_entity.cpp:195
auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override
Definition: pedestrian_entity.cpp:127
void setAccelerationRateLimit(double acceleration_rate) override
Definition: pedestrian_entity.cpp:225
auto getGoalPoses() -> std::vector< CanonicalizedLaneletPose > override
Definition: pedestrian_entity.cpp:122
auto requestFollowTrajectory(const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void override
Definition: pedestrian_entity.cpp:81
void setDecelerationRateLimit(double deceleration) override
Definition: pedestrian_entity.cpp:245
const traffic_simulator_msgs::msg::PedestrianParameters pedestrian_parameters
Definition: pedestrian_entity.hpp:128
auto getEntityType() const -> const traffic_simulator_msgs::msg::EntityType &override
Definition: pedestrian_entity.cpp:163
auto getMaxDeceleration() const -> double override
Definition: pedestrian_entity.cpp:200
void setAccelerationLimit(double acceleration) override
Definition: pedestrian_entity.cpp:215
void setVelocityLimit(double linear_velocity) override
Definition: pedestrian_entity.cpp:205
std::string getCurrentAction() const override
Definition: pedestrian_entity.cpp:88
auto getObstacle() -> std::optional< traffic_simulator_msgs::msg::Obstacle > override
Definition: pedestrian_entity.cpp:117
void setTrafficLightManager(const std::shared_ptr< traffic_simulator::TrafficLightManager > &ptr) override
Definition: pedestrian_entity.cpp:176
PedestrianEntity(const std::string &name, const CanonicalizedEntityStatus &, const std::shared_ptr< hdmap_utils::HdMapUtils > &, const traffic_simulator_msgs::msg::PedestrianParameters &, const std::string &plugin_name=BuiltinBehavior::defaultBehavior())
Definition: pedestrian_entity.cpp:25
auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter
Definition: pedestrian_entity.cpp:183
void appendDebugMarker(visualization_msgs::msg::MarkerArray &marker_array) override
Definition: pedestrian_entity.cpp:47
const std::string plugin_name
Definition: pedestrian_entity.hpp:126
auto fillLaneletPose(CanonicalizedEntityStatus &status) -> void override
Definition: pedestrian_entity.cpp:255
void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &)
Definition: pedestrian_entity.cpp:189
void requestAcquirePosition(const CanonicalizedLaneletPose &lanelet_pose) override
Definition: pedestrian_entity.cpp:137
auto getRouteLanelets(double horizon=100) -> lanelet::Ids override
Definition: pedestrian_entity.cpp:107
void cancelRequest() override
Definition: pedestrian_entity.cpp:157
void setDecelerationLimit(double deceleration) override
Definition: pedestrian_entity.cpp:235
Definition: entity_status.hpp:29
Definition: lanelet_pose.hpp:27
Definition: action_node.hpp:38
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