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;
71 auto
onUpdate(const
double current_time, const
double step_time) ->
void override;
106 const
std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> &) ->
void override;
111 -> const traffic_simulator_msgs::msg::DynamicConstraints & override;
115 auto
getParameters() const -> const traffic_simulator_msgs::msg::PedestrianParameters &;
117 auto
getObstacle() ->
std::optional<traffic_simulator_msgs::msg::Obstacle> override;
121 auto
getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override;
Definition: route_planner.hpp:27
Definition: traffic_lights_base.hpp:39
Definition: entity_base.hpp:51
const std::string name
Definition: entity_base.hpp:307
Definition: pedestrian_entity.hpp:34
void requestWalkStraight() override
Definition: pedestrian_entity.cpp:135
auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
Definition: pedestrian_entity.cpp:96
auto getGoalPoses() -> std::vector< geometry_msgs::msg::Pose > override
Definition: pedestrian_entity.cpp:121
~PedestrianEntity() override=default
void requestAssignRoute(const std::vector< CanonicalizedLaneletPose > &waypoints) override
Definition: pedestrian_entity.cpp:54
auto getEntityTypename() const -> const std::string &override
Definition: pedestrian_entity.cpp:168
auto getMaxAcceleration() const -> double override
Definition: pedestrian_entity.cpp:199
auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override
Definition: pedestrian_entity.cpp:130
void setAccelerationRateLimit(double acceleration_rate) override
Definition: pedestrian_entity.cpp:229
auto requestFollowTrajectory(const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void override
Definition: pedestrian_entity.cpp:84
void setDecelerationRateLimit(double deceleration) override
Definition: pedestrian_entity.cpp:249
const traffic_simulator_msgs::msg::PedestrianParameters pedestrian_parameters
Definition: pedestrian_entity.hpp:125
void setTrafficLights(const std::shared_ptr< traffic_simulator::TrafficLightsBase > &ptr) override
Definition: pedestrian_entity.cpp:174
auto getMaxDeceleration() const -> double override
Definition: pedestrian_entity.cpp:204
void setAccelerationLimit(double acceleration) override
Definition: pedestrian_entity.cpp:219
void setVelocityLimit(double linear_velocity) override
Definition: pedestrian_entity.cpp:209
std::string getCurrentAction() const override
Definition: pedestrian_entity.cpp:91
auto getParameters() const -> const traffic_simulator_msgs::msg::PedestrianParameters &
Definition: pedestrian_entity.cpp:181
auto getObstacle() -> std::optional< traffic_simulator_msgs::msg::Obstacle > override
Definition: pedestrian_entity.cpp:116
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:26
auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter
Definition: pedestrian_entity.cpp:187
void appendDebugMarker(visualization_msgs::msg::MarkerArray &marker_array) override
Definition: pedestrian_entity.cpp:48
const std::string plugin_name
Definition: pedestrian_entity.hpp:123
auto onUpdate(const double current_time, const double step_time) -> void override
Definition: pedestrian_entity.cpp:259
void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &)
Definition: pedestrian_entity.cpp:193
void requestAcquirePosition(const CanonicalizedLaneletPose &lanelet_pose) override
Definition: pedestrian_entity.cpp:140
auto getRouteLanelets(double horizon=100) -> lanelet::Ids override
Definition: pedestrian_entity.cpp:107
void cancelRequest() override
Definition: pedestrian_entity.cpp:162
void setDecelerationLimit(double deceleration) override
Definition: pedestrian_entity.cpp:239
Definition: entity_status.hpp:32
Definition: lanelet_pose.hpp:28
Definition: action_node.hpp:40
Definition: lanelet_wrapper.hpp:40
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
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