scenario_simulator_v2 C++ API
vehicle_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__VEHICLE_ENTITY_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__VEHICLE_ENTITY_HPP_
17 
18 #include <memory>
19 #include <optional>
20 #include <pluginlib/class_loader.hpp>
21 #include <pugixml.hpp>
22 #include <rclcpp/rclcpp.hpp>
23 #include <string>
27 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
28 #include <traffic_simulator_msgs/msg/vehicle_parameters.hpp>
29 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
30 #include <vector>
31 
32 namespace traffic_simulator
33 {
34 namespace entity
35 {
36 class VehicleEntity : public EntityBase
37 {
38 public:
40  {
41  static auto behaviorTree() -> const std::string &
42  {
43  static const std::string name = "behavior_tree_plugin/VehicleBehaviorTree";
44  return name;
45  }
46 
47  static auto contextGamma() -> const std::string &
48  {
49  static const std::string name = "context_gamma_planner/VehiclePlugin";
50  return name;
51  }
52 
53  static auto doNothing() noexcept -> const std::string &
54  {
55  static const std::string name = "do_nothing_plugin/DoNothingPlugin";
56  return name;
57  }
58 
59  static auto defaultBehavior() -> const std::string & { return behaviorTree(); }
60  };
61 
62  explicit VehicleEntity(
64  const std::shared_ptr<hdmap_utils::HdMapUtils> &,
65  const traffic_simulator_msgs::msg::VehicleParameters &,
66  const std::string & plugin_name = BuiltinBehavior::defaultBehavior());
67 
68  ~VehicleEntity() override = default;
69 
70  void appendDebugMarker(visualization_msgs::msg::MarkerArray & marker_array) override;
71 
72  void cancelRequest() override;
73 
74  auto getCurrentAction() const -> std::string override;
75 
76  auto getDefaultDynamicConstraints() const
77  -> const traffic_simulator_msgs::msg::DynamicConstraints & override;
78 
79  auto getDefaultMatchingDistanceForLaneletPoseCalculation() const -> double override;
80 
81  auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter override;
82 
83  auto getMaxAcceleration() const -> double override;
84 
85  auto getMaxDeceleration() const -> double override;
86 
87  auto getEntityTypename() const -> const std::string & override;
88 
89  auto getGoalPoses() -> std::vector<CanonicalizedLaneletPose> override;
90 
91  auto getObstacle() -> std::optional<traffic_simulator_msgs::msg::Obstacle> override;
92 
93  auto getRouteLanelets(double horizon = 100) -> lanelet::Ids override;
94 
95  auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override;
96 
97  auto onUpdate(const double current_time, const double step_time) -> void override;
98 
100 
101  void requestAcquirePosition(const geometry_msgs::msg::Pose & map_pose) override;
102 
103  void requestAssignRoute(const std::vector<geometry_msgs::msg::Pose> &) override;
104 
105  void requestAssignRoute(const std::vector<CanonicalizedLaneletPose> &) override;
106 
108  const std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> &) -> void override;
109 
110  void requestLaneChange(const lanelet::Id to_lanelet_id) override;
111 
112  void requestLaneChange(const traffic_simulator::lane_change::Parameter &) override;
113 
114  void setVelocityLimit(double linear_velocity) override;
115 
116  void setAccelerationLimit(double acceleration) override;
117 
118  void setAccelerationRateLimit(double acceleration_rate) override;
119 
120  void setDecelerationLimit(double deceleration) override;
121 
122  void setDecelerationRateLimit(double deceleration_rate) override;
123 
124  void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &) override;
125 
126  void setTrafficLights(const std::shared_ptr<traffic_simulator::TrafficLightsBase> &) override;
127 
128  const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters;
129 
130 private:
131  pluginlib::ClassLoader<entity_behavior::BehaviorPluginBase> loader_;
132 
133  const std::shared_ptr<entity_behavior::BehaviorPluginBase> behavior_plugin_ptr_;
134 
135  traffic_simulator::RoutePlanner route_planner_;
136 
137  std::shared_ptr<math::geometry::CatmullRomSpline> spline_;
138 
139  lanelet::Ids previous_route_lanelets_;
140 };
141 } // namespace entity
142 } // namespace traffic_simulator
143 
144 #endif // TRAFFIC_SIMULATOR__ENTITY__VEHICLE_ENTITY_HPP_
Definition: route_planner.hpp:27
Definition: traffic_lights_base.hpp:39
Definition: entity_base.hpp:51
const std::string name
Definition: entity_base.hpp:255
Definition: vehicle_entity.hpp:37
void setDecelerationLimit(double deceleration) override
Definition: vehicle_entity.cpp:294
auto getEntityTypename() const -> const std::string &override
Definition: vehicle_entity.cpp:89
auto getGoalPoses() -> std::vector< CanonicalizedLaneletPose > override
Definition: vehicle_entity.cpp:95
auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override
Definition: vehicle_entity.cpp:114
void setVelocityLimit(double linear_velocity) override
Definition: vehicle_entity.cpp:264
void setAccelerationLimit(double acceleration) override
Definition: vehicle_entity.cpp:274
void requestAssignRoute(const std::vector< geometry_msgs::msg::Pose > &) override
Definition: vehicle_entity.cpp:198
void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &) override
Definition: vehicle_entity.cpp:314
auto getCurrentAction() const -> std::string override
Definition: vehicle_entity.cpp:60
auto getDefaultMatchingDistanceForLaneletPoseCalculation() const -> double override
Definition: vehicle_entity.cpp:72
auto requestFollowTrajectory(const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void override
Definition: vehicle_entity.cpp:214
auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
Definition: vehicle_entity.cpp:65
VehicleEntity(const std::string &name, const CanonicalizedEntityStatus &, const std::shared_ptr< hdmap_utils::HdMapUtils > &, const traffic_simulator_msgs::msg::VehicleParameters &, const std::string &plugin_name=BuiltinBehavior::defaultBehavior())
Definition: vehicle_entity.cpp:27
void appendDebugMarker(visualization_msgs::msg::MarkerArray &marker_array) override
Definition: vehicle_entity.cpp:48
auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter override
Definition: vehicle_entity.cpp:84
void requestAcquirePosition(const CanonicalizedLaneletPose &)
Definition: vehicle_entity.cpp:162
void requestLaneChange(const lanelet::Id to_lanelet_id) override
Definition: vehicle_entity.cpp:235
auto onUpdate(const double current_time, const double step_time) -> void override
Definition: vehicle_entity.cpp:129
void setAccelerationRateLimit(double acceleration_rate) override
Definition: vehicle_entity.cpp:284
const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters
Definition: vehicle_entity.hpp:128
void setDecelerationRateLimit(double deceleration_rate) override
Definition: vehicle_entity.cpp:304
auto getMaxAcceleration() const -> double override
Definition: vehicle_entity.cpp:250
auto getMaxDeceleration() const -> double override
Definition: vehicle_entity.cpp:257
auto getRouteLanelets(double horizon=100) -> lanelet::Ids override
Definition: vehicle_entity.cpp:105
void cancelRequest() override
Definition: vehicle_entity.cpp:54
void setTrafficLights(const std::shared_ptr< traffic_simulator::TrafficLightsBase > &) override
Definition: vehicle_entity.cpp:320
auto getObstacle() -> std::optional< traffic_simulator_msgs::msg::Obstacle > override
Definition: vehicle_entity.cpp:100
Definition: entity_status.hpp:32
Definition: lanelet_pose.hpp:27
Definition: action_node.hpp:39
Definition: bounding_box.hpp:32
Definition: cache.hpp:27
Definition: api.hpp:49
std::string string
Definition: junit5.hpp:26
static auto defaultBehavior() -> const std::string &
Definition: vehicle_entity.hpp:59
static auto doNothing() noexcept -> const std::string &
Definition: vehicle_entity.hpp:53
static auto behaviorTree() -> const std::string &
Definition: vehicle_entity.hpp:41
static auto contextGamma() -> const std::string &
Definition: vehicle_entity.hpp:47