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 std::shared_ptr<hdmap_utils::HdMapUtils> &,
62  const traffic_simulator_msgs::msg::PedestrianParameters &,
64 
65  ~PedestrianEntity() override = default;
66 
67  void appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) override;
68 
69  auto getEntityType() const -> const traffic_simulator_msgs::msg::EntityType & override;
70 
71  auto getEntityTypename() const -> const std::string & override;
72 
73  void onUpdate(double current_time, double step_time) override;
74 
75  void requestAcquirePosition(const CanonicalizedLaneletPose & lanelet_pose) override;
76 
77  void requestAcquirePosition(const geometry_msgs::msg::Pose & map_pose) override;
78 
79  void requestWalkStraight() override;
80 
81  void cancelRequest() override;
82 
84  const std::shared_ptr<traffic_simulator::TrafficLightManager> & ptr) override;
85 
86  auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter;
87 
88  auto getMaxAcceleration() const -> double override;
89 
90  auto getMaxDeceleration() const -> double override;
91 
92  void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &);
93 
94  void setVelocityLimit(double linear_velocity) override;
95 
96  void setAccelerationLimit(double acceleration) override;
97 
98  void setAccelerationRateLimit(double acceleration_rate) override;
99 
100  void setDecelerationLimit(double deceleration) override;
101 
102  void setDecelerationRateLimit(double deceleration) override;
103 
104  void requestAssignRoute(const std::vector<CanonicalizedLaneletPose> & waypoints) override;
105 
106  void requestAssignRoute(const std::vector<geometry_msgs::msg::Pose> &) 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 getObstacle() -> std::optional<traffic_simulator_msgs::msg::Obstacle> override;
119 
120  auto getGoalPoses() -> std::vector<CanonicalizedLaneletPose> override;
121 
122  auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override;
123 
124  auto fillLaneletPose(CanonicalizedEntityStatus & status) -> void 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 };
135 } // namespace entity
136 } // namespace traffic_simulator
137 
138 #endif // TRAFFIC_SIMULATOR__ENTITY__PEDESTRIAN_ENTITY_HPP_
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
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
Definition: cache.hpp:27
Definition: api.hpp:48
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