scenario_simulator_v2 C++ API
pedestrian_entity.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 TRAFFIC_SIMULATOR__ENTITY__PEDESTRIAN_ENTITY_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__PEDESTRIAN_ENTITY_HPP_
17 
18 #include <memory>
19 #include <optional>
20 #include <pluginlib/class_loader.hpp>
21 #include <pugixml.hpp>
22 #include <string>
26 #include <traffic_simulator_msgs/msg/pedestrian_parameters.hpp>
27 #include <vector>
28 
29 namespace traffic_simulator
30 {
31 namespace entity
32 {
34 {
35 public:
37  {
38  static auto behaviorTree() noexcept -> const std::string &
39  {
40  static const std::string name = "behavior_tree_plugin/PedestrianBehaviorTree";
41  return name;
42  }
43 
44  static auto contextGamma() noexcept -> const std::string &
45  {
46  static const std::string name = "context_gamma_planner/PedestrianPlugin";
47  return name;
48  }
49 
50  static auto doNothing() noexcept -> const std::string &
51  {
52  static const std::string name = "do_nothing_plugin/DoNothingPlugin";
53  return name;
54  }
55 
56  static auto defaultBehavior() noexcept -> const std::string & { return behaviorTree(); }
57  };
58 
59  explicit PedestrianEntity(
61  const traffic_simulator_msgs::msg::PedestrianParameters &,
63 
64  ~PedestrianEntity() override = default;
65 
66  void appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) override;
67 
68  auto getEntityTypename() const -> const std::string & override;
69 
70  auto onUpdate(const double current_time, const double step_time) -> void override;
71 
73  const CanonicalizedLaneletPose & lanelet_pose, const RouteOption &) override;
74 
76  const geometry_msgs::msg::Pose & map_pose, const RouteOption &) override;
77 
78  void requestWalkStraight() override;
79 
80  void cancelRequest() override;
81 
82  void setTrafficLights(const std::shared_ptr<traffic_simulator::TrafficLightsBase> & ptr) override;
83 
84  auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter;
85 
86  auto getMaxAcceleration() const -> double override;
87 
88  auto getMaxDeceleration() const -> double override;
89 
90  void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &);
91 
92  void setVelocityLimit(double linear_velocity) override;
93 
94  void setAccelerationLimit(double acceleration) override;
95 
96  void setAccelerationRateLimit(double acceleration_rate) override;
97 
98  void setDecelerationLimit(double deceleration) override;
99 
100  void setDecelerationRateLimit(double deceleration) override;
101 
102  void requestAssignRoute(
103  const std::vector<CanonicalizedLaneletPose> & waypoints, const RouteOption &) override;
104 
105  void requestAssignRoute(
106  const std::vector<geometry_msgs::msg::Pose> &, const RouteOption &) override;
107 
109  const std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> &) -> void override;
110 
111  std::string getCurrentAction() const override;
112 
113  auto getDefaultDynamicConstraints() const
114  -> const traffic_simulator_msgs::msg::DynamicConstraints & override;
115 
116  auto getRouteLanelets(double horizon = 100) -> lanelet::Ids override;
117 
118  auto getParameters() const -> const traffic_simulator_msgs::msg::PedestrianParameters &;
119 
120  auto getObstacle() -> std::optional<traffic_simulator_msgs::msg::Obstacle> override;
121 
122  auto getGoalPoses() -> std::vector<geometry_msgs::msg::Pose> override;
123 
124  auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override;
125 
126  const std::string plugin_name;
127 
128  const traffic_simulator_msgs::msg::PedestrianParameters pedestrian_parameters;
129 
130 private:
131  pluginlib::ClassLoader<entity_behavior::BehaviorPluginBase> loader_;
132  const std::shared_ptr<entity_behavior::BehaviorPluginBase> behavior_plugin_ptr_;
133  traffic_simulator::RoutePlanner route_planner_{
134  traffic_simulator::RoutingGraphType::VEHICLE_WITH_ROAD_SHOULDER};
135 };
136 } // namespace entity
137 } // namespace traffic_simulator
138 
139 #endif // TRAFFIC_SIMULATOR__ENTITY__PEDESTRIAN_ENTITY_HPP_
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
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
Definition: api.hpp:33
std::string string
Definition: junit5.hpp:26
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