scenario_simulator_v2 C++ API
entity_base.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__ENTITY_BASE_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__ENTITY_BASE_HPP_
17 
18 #include <autoware_control_msgs/msg/control.hpp>
19 #include <autoware_vehicle_msgs/msg/gear_command.hpp>
21 #include <memory>
22 #include <optional>
23 #include <queue>
24 #include <string>
35 #include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
36 #include <traffic_simulator_msgs/msg/bounding_box.hpp>
37 #include <traffic_simulator_msgs/msg/entity_status.hpp>
38 #include <traffic_simulator_msgs/msg/entity_type.hpp>
39 #include <traffic_simulator_msgs/msg/obstacle.hpp>
40 #include <traffic_simulator_msgs/msg/vehicle_parameters.hpp>
41 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
42 #include <unordered_map>
43 #include <vector>
44 #include <visualization_msgs/msg/marker_array.hpp>
45 
46 namespace traffic_simulator
47 {
48 namespace entity
49 {
50 using EuclideanDistancesMap = std::unordered_map<std::pair<std::string, std::string>, double>;
51 class EntityBase : public std::enable_shared_from_this<EntityBase>
52 {
53 public:
54  explicit EntityBase(const std::string & name, const CanonicalizedEntityStatus & entity_status);
55 
56  EntityBase(const EntityBase &) = delete;
57 
58  EntityBase & operator=(const EntityBase &) = delete;
59 
60  EntityBase(EntityBase &&) noexcept = delete;
61 
62  EntityBase & operator=(EntityBase &&) noexcept = delete;
63 
64  virtual ~EntityBase() = default;
65 
66  template <typename EntityType>
67  /* */ auto is() const -> bool
68  {
69  return dynamic_cast<EntityType const *>(this) != nullptr;
70  }
71 
72  template <typename EntityType>
73  /* */ auto as() -> EntityType &
74  {
75  if (const auto derived_ptr = dynamic_cast<EntityType *>(this); !derived_ptr) {
77  "Entity ", std::quoted(name), " is not ", std::quoted(typeid(EntityType).name()), "type");
78  } else {
79  return *derived_ptr;
80  }
81  }
82 
83  template <typename EntityType>
84  /* */ auto as() const -> const EntityType &
85  {
86  if (const auto derived_ptr = dynamic_cast<EntityType const *>(this); !derived_ptr) {
88  "Entity ", std::quoted(name), " is not ", std::quoted(typeid(EntityType).name()), "type");
89  } else {
90  return *derived_ptr;
91  }
92  }
93 
94  virtual void appendDebugMarker(visualization_msgs::msg::MarkerArray & /*unused*/);
95 
96  virtual void cancelRequest();
97 
98  // clang-format off
99 #define DEFINE_GETTER(NAME, TYPE, RETURN_VARIABLE) \
100  \
105  /* */ auto get##NAME() const noexcept->TYPE { return RETURN_VARIABLE; }
106 
108  DEFINE_GETTER(CanonicalizedStatus, const CanonicalizedEntityStatus &, *status_)
109  DEFINE_GETTER(CanonicalizedStatusBeforeUpdate, const CanonicalizedEntityStatus &, status_before_update_)
110  DEFINE_GETTER(CurrentAccel, const geometry_msgs::msg::Accel &, status_->getAccel())
111  DEFINE_GETTER(CurrentTwist, const geometry_msgs::msg::Twist &, status_->getTwist())
112  DEFINE_GETTER(DynamicConstraints, traffic_simulator_msgs::msg::DynamicConstraints, getBehaviorParameter().dynamic_constraints)
115  DEFINE_GETTER(LinearJerk, double, status_->getLinearJerk())
116  DEFINE_GETTER(MapPose, const geometry_msgs::msg::Pose &, status_->getMapPose())
117  DEFINE_GETTER(StandStillDuration, double, stand_still_duration_)
118  DEFINE_GETTER(TraveledDistance, double, traveled_distance_)
119  DEFINE_GETTER(Name, const std::string &, status_->getName())
120  // clang-format on
121 #undef DEFINE_GETTER
122 
123  /* */ auto get2DPolygon() const -> std::vector<geometry_msgs::msg::Point>;
124 
125  virtual auto getCurrentAction() const -> std::string = 0;
126 
127  virtual auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter = 0;
128 
129  virtual auto getDefaultDynamicConstraints() const
130  -> const traffic_simulator_msgs::msg::DynamicConstraints & = 0;
131 
132  virtual auto getEntityTypename() const -> const std::string & = 0;
133 
134  virtual auto getGoalPoses() -> std::vector<geometry_msgs::msg::Pose> = 0;
135 
136  /* */ auto isStopped() const -> bool;
137 
138  /* */ auto isNearbyPosition(const geometry_msgs::msg::Pose & pose, const double tolerance) const
139  -> bool;
140 
141  /* */ auto isNearbyPosition(
142  const CanonicalizedLaneletPose & lanelet_pose, const double tolerance) const -> bool;
143 
144  /* */ auto isInLanelet() const -> bool { return status_->isInLanelet(); };
145 
146  /* */ auto isInLanelet(
147  const lanelet::Id lanelet_id, std::optional<double> tolerance = std::nullopt) const -> bool;
148 
149  /* */ auto getCanonicalizedLaneletPose() const -> std::optional<CanonicalizedLaneletPose>;
150 
151  /* */ auto getCanonicalizedLaneletPose(const double matching_distance) const
153 
154  virtual auto getMaxAcceleration() const -> double = 0;
155 
156  virtual auto getMaxDeceleration() const -> double = 0;
157 
159 
160  virtual auto getObstacle() -> std::optional<traffic_simulator_msgs::msg::Obstacle> = 0;
161 
162  virtual auto getRouteLanelets(const double horizon = 100.0) -> lanelet::Ids = 0;
163 
164  virtual auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray = 0;
165 
166  virtual auto onUpdate(const double current_time, const double step_time) -> void;
167 
168  virtual auto onPostUpdate(const double current_time, const double step_time) -> void;
169 
170  /* */ void resetDynamicConstraints();
171 
172  [[deprecated(
173  "This function was deprecated since version 16.4.0 (released on 20250522). It will be deleted "
174  "after a half-year transition period (~20251122). Please use one with RouteOption argument "
175  "instead.")]] virtual void
177  {
178  return requestAcquirePosition(pose, {});
179  }
180 
181  virtual void requestAcquirePosition(const CanonicalizedLaneletPose &, const RouteOption &) = 0;
182 
183  [[deprecated(
184  "This function was deprecated since version 16.4.0 (released on 20250522). It will be deleted "
185  "after a half-year transition period (~20251122). Please use one with RouteOption argument "
186  "instead.")]] virtual void
188  {
189  return requestAcquirePosition(pose, {});
190  }
191 
192  virtual void requestAcquirePosition(const geometry_msgs::msg::Pose &, const RouteOption &) = 0;
193 
194  [[deprecated(
195  "This function was deprecated since version 16.4.0 (released on 20250522). It will be deleted "
196  "after a half-year transition period (~20251122). Please use one with RouteOption argument "
197  "instead.")]] virtual void
198  requestAssignRoute(const std::vector<CanonicalizedLaneletPose> & pose)
199  {
200  return requestAssignRoute(pose, {});
201  }
202 
203  virtual void requestAssignRoute(
204  const std::vector<CanonicalizedLaneletPose> &, const RouteOption &) = 0;
205 
206  [[deprecated(
207  "This function was deprecated since version 16.4.0 (released on 20250522). It will be deleted "
208  "after a half-year transition period (~20251122). Please use one with RouteOption argument "
209  "instead.")]] virtual void
210  requestAssignRoute(const std::vector<geometry_msgs::msg::Pose> & pose)
211  {
212  return requestAssignRoute(pose, {});
213  }
214 
215  virtual void requestAssignRoute(
216  const std::vector<geometry_msgs::msg::Pose> &, const RouteOption &) = 0;
217 
218  virtual auto requestLaneChange(const lanelet::Id) -> void
219  {
224  }
225 
226  virtual auto requestLaneChange(const lane_change::Parameter &) -> void
227  {
232  }
233 
234  /* */ auto requestLaneChange(const lane_change::Direction & direction) -> void;
235 
236  /* */ auto requestLaneChange(
237  const lane_change::AbsoluteTarget & target, const lane_change::TrajectoryShape trajectory_shape,
238  const lane_change::Constraint & constraint) -> void;
239 
240  /* */ auto requestLaneChange(
241  const lane_change::RelativeTarget & target, const lane_change::TrajectoryShape trajectory_shape,
242  const lane_change::Constraint & constraint) -> void;
243 
244  virtual auto requestSpeedChange(
245  const double target_speed, const speed_change::Transition,
246  const speed_change::Constraint constraint, const bool continuous) -> void;
247 
248  virtual void requestSpeedChange(
249  const speed_change::RelativeTargetSpeed & target_speed,
250  const speed_change::Transition transition, const speed_change::Constraint constraint,
251  const bool continuous);
252 
253  virtual void requestSpeedChange(const double target_speed, const bool continuous);
254 
255  virtual void requestSpeedChange(
256  const speed_change::RelativeTargetSpeed & target_speed, const bool continuous);
257 
258  virtual auto isControlledBySimulator() const -> bool;
259 
260  virtual auto setControlledBySimulator(const bool /*unused*/) -> void;
261 
262  virtual auto requestFollowTrajectory(
263  const std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> & /*unused*/) -> void;
264 
265  virtual void requestWalkStraight();
266 
267  virtual void setAccelerationLimit(const double acceleration) = 0;
268 
269  virtual void setAccelerationRateLimit(const double acceleration_rate) = 0;
270 
271  virtual void setDecelerationLimit(const double deceleration) = 0;
272 
273  virtual void setDecelerationRateLimit(const double deceleration_rate) = 0;
274 
275  /* */ void setDynamicConstraints(
276  const traffic_simulator_msgs::msg::DynamicConstraints & constraints);
277 
278  virtual void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &) = 0;
279 
280  /* */ void setOtherStatus(
281  const std::unordered_map<std::string, CanonicalizedEntityStatus> & status);
282 
283  /* */ auto setCanonicalizedStatus(const CanonicalizedEntityStatus & status) -> void;
284 
285  virtual auto setStatus(const EntityStatus & status) -> void;
286 
287  virtual auto setStatus(const EntityStatus & status, const lanelet::Ids & lanelet_ids) -> void;
288 
289  virtual auto setStatus(
290  const geometry_msgs::msg::Pose & map_pose,
291  const traffic_simulator_msgs::msg::ActionStatus & action_status =
292  helper::constructActionStatus()) -> void;
293 
294  virtual auto setStatus(
295  const geometry_msgs::msg::Pose & reference_pose, const geometry_msgs::msg::Pose & relative_pose,
296  const traffic_simulator_msgs::msg::ActionStatus & action_status =
297  helper::constructActionStatus()) -> void;
298 
299  virtual auto setStatus(
300  const geometry_msgs::msg::Pose & reference_pose,
301  const geometry_msgs::msg::Point & relative_position,
302  const geometry_msgs::msg::Vector3 & relative_rpy,
303  const traffic_simulator_msgs::msg::ActionStatus & action_status =
304  helper::constructActionStatus()) -> void;
305 
306  virtual auto setStatus(
307  const CanonicalizedLaneletPose & canonicalized_lanelet_pose,
308  const traffic_simulator_msgs::msg::ActionStatus & action_status =
309  helper::constructActionStatus()) -> void;
310 
311  virtual auto setStatus(
312  const LaneletPose & lanelet_pose,
313  const traffic_simulator_msgs::msg::ActionStatus & action_status =
314  helper::constructActionStatus()) -> void;
315 
316  virtual auto setLinearAcceleration(const double linear_acceleration) -> void;
317 
318  virtual auto setLinearVelocity(const double linear_velocity) -> void;
319 
320  virtual void setTrafficLights(
321  const std::shared_ptr<traffic_simulator::TrafficLightsBase> & traffic_lights);
322 
323  virtual auto activateOutOfRangeJob(
324  const double min_velocity, const double max_velocity, const double min_acceleration,
325  const double max_acceleration, const double min_jerk, const double max_jerk) -> void;
326 
327  virtual auto setVelocityLimit(const double) -> void = 0;
328 
329  // Optional per-entity lateral collision margin (meters).
330  // Default no-op for entities that do not use BT-based lateral collision checks.
331  virtual void setLateralCollisionThreshold(const std::optional<double> &) {}
332 
333  virtual auto setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void;
334 
335  /* */ auto setTwist(const geometry_msgs::msg::Twist & twist) -> void;
336 
337  /* */ auto setAcceleration(const geometry_msgs::msg::Accel & accel) -> void;
338 
339  /* */ auto setAction(const std::string & action) -> void;
340 
341  /* */ auto setLinearJerk(const double liner_jerk) -> void;
342 
343  /* */ void stopAtCurrentPosition();
344 
345  /* */ void updateEntityStatusTimestamp(const double current_time);
346 
347  /* */ auto requestSynchronize(
348  const std::string & target_name, const CanonicalizedLaneletPose & target_sync_pose,
349  const CanonicalizedLaneletPose & entity_target, const double target_speed,
350  const double tolerance) -> bool;
351 
352  const std::string name;
353 
354  bool verbose;
355 
356  void setEuclideanDistancesMap(const std::shared_ptr<EuclideanDistancesMap> & distances);
357 
358 protected:
359  std::shared_ptr<CanonicalizedEntityStatus> status_;
360 
362 
363  std::shared_ptr<traffic_simulator::TrafficLightsBase> traffic_lights_;
364 
365  double stand_still_duration_ = 0.0;
366  double traveled_distance_ = 0.0;
367  double prev_job_duration_ = 0.0;
368  double step_time_ = 0.0;
369 
370  std::unordered_map<std::string, CanonicalizedEntityStatus> other_status_;
371 
372  std::optional<double> target_speed_;
374 
375  std::unique_ptr<traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner>
377 
378  std::shared_ptr<EuclideanDistancesMap> euclidean_distances_map_;
379 
380 private:
381  virtual auto requestSpeedChangeWithConstantAcceleration(
382  const double target_speed, const speed_change::Transition, const double acceleration,
383  const bool continuous) -> void;
384  virtual auto requestSpeedChangeWithConstantAcceleration(
385  const speed_change::RelativeTargetSpeed & target_speed,
386  const speed_change::Transition transition, const double acceleration, const bool continuous)
387  -> void;
388  virtual auto requestSpeedChangeWithTimeConstraint(
389  const double target_speed, const speed_change::Transition, const double acceleration_time)
390  -> void;
391  virtual auto requestSpeedChangeWithTimeConstraint(
392  const speed_change::RelativeTargetSpeed & target_speed,
393  const speed_change::Transition transition, const double time) -> void;
394  /* */ auto isTargetSpeedReached(const double target_speed) const -> bool;
395  /* */ auto isTargetSpeedReached(const speed_change::RelativeTargetSpeed & target_speed) const
396  -> bool;
397 };
398 } // namespace entity
399 } // namespace traffic_simulator
400 
401 #endif // TRAFFIC_SIMULATOR__ENTITY__ENTITY_BASE_HPP_
Definition: traffic_lights_base.hpp:44
Definition: entity_base.hpp:52
auto setTwist(const geometry_msgs::msg::Twist &twist) -> void
Definition: entity_base.cpp:664
virtual auto setLinearAcceleration(const double linear_acceleration) -> void
Definition: entity_base.cpp:653
virtual void setDecelerationLimit(const double deceleration)=0
CanonicalizedEntityStatus status_before_update_
Definition: entity_base.hpp:357
auto setLinearJerk(const double liner_jerk) -> void
Definition: entity_base.cpp:674
virtual void setDecelerationRateLimit(const double deceleration_rate)=0
virtual auto requestFollowTrajectory(const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void
Definition: entity_base.cpp:549
auto as() const -> const EntityType &
Definition: entity_base.hpp:84
virtual auto requestSpeedChange(const double target_speed, const speed_change::Transition, const speed_change::Constraint constraint, const bool continuous) -> void
Definition: entity_base.cpp:323
auto is() const -> bool
Definition: entity_base.hpp:67
virtual void setAccelerationLimit(const double acceleration)=0
double stand_still_duration_
Definition: entity_base.hpp:361
virtual auto onUpdate(const double current_time, const double step_time) -> void
Definition: entity_base.cpp:141
virtual void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &)=0
void stopAtCurrentPosition()
Definition: entity_base.cpp:729
auto isNearbyPosition(const geometry_msgs::msg::Pose &pose, const double tolerance) const -> bool
Definition: entity_base.cpp:96
traffic_simulator::job::JobList job_list_
Definition: entity_base.hpp:369
void setOtherStatus(const std::unordered_map< std::string, CanonicalizedEntityStatus > &status)
Definition: entity_base.cpp:569
virtual auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints &=0
auto requestSynchronize(const std::string &target_name, const CanonicalizedLaneletPose &target_sync_pose, const CanonicalizedLaneletPose &entity_target, const double target_speed, const double tolerance) -> bool
Definition: entity_base.cpp:750
const std::string name
Definition: entity_base.hpp:348
void resetDynamicConstraints()
Definition: entity_base.cpp:156
EntityBase(const EntityBase &)=delete
std::unordered_map< std::string, CanonicalizedEntityStatus > other_status_
Definition: entity_base.hpp:366
virtual auto getCurrentAction() const -> std::string=0
virtual auto isControlledBySimulator() const -> bool
Definition: entity_base.cpp:541
virtual auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter=0
void setEuclideanDistancesMap(const std::shared_ptr< EuclideanDistancesMap > &distances)
Definition: entity_base.cpp:852
double step_time_
Definition: entity_base.hpp:364
auto isStopped() const -> bool
Definition: entity_base.cpp:124
std::shared_ptr< EuclideanDistancesMap > euclidean_distances_map_
Definition: entity_base.hpp:374
auto getLinearJerk() const noexcept -> double
Get LinearJerk of the entity.
Definition: entity_base.hpp:111
virtual void appendDebugMarker(visualization_msgs::msg::MarkerArray &)
Definition: entity_base.cpp:68
virtual auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray=0
virtual void setAccelerationRateLimit(const double acceleration_rate)=0
virtual void cancelRequest()
Definition: entity_base.cpp:70
std::unique_ptr< traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner > speed_planner_
Definition: entity_base.hpp:372
virtual void requestWalkStraight()
Definition: entity_base.cpp:556
virtual auto onPostUpdate(const double current_time, const double step_time) -> void
Definition: entity_base.cpp:151
virtual void requestAcquirePosition(const CanonicalizedLaneletPose &pose)
Definition: entity_base.hpp:172
virtual auto requestLaneChange(const lanelet::Id) -> void
Definition: entity_base.hpp:214
auto setAcceleration(const geometry_msgs::msg::Accel &accel) -> void
Definition: entity_base.cpp:669
auto getCanonicalizedLaneletPose() const -> std::optional< CanonicalizedLaneletPose >
Definition: entity_base.cpp:77
auto getName() const noexcept -> const std::string &
Get Name of the entity.
Definition: entity_base.hpp:115
void setDynamicConstraints(const traffic_simulator_msgs::msg::DynamicConstraints &constraints)
Definition: entity_base.cpp:561
virtual auto getEntityTypename() const -> const std::string &=0
auto setAction(const std::string &action) -> void
Definition: entity_base.cpp:679
auto getMapPose() const noexcept -> const geometry_msgs::msg::Pose &
Get MapPose of the entity.
Definition: entity_base.hpp:112
virtual auto setControlledBySimulator(const bool) -> void
Definition: entity_base.cpp:543
double prev_job_duration_
Definition: entity_base.hpp:363
bool verbose
Definition: entity_base.hpp:350
virtual auto activateOutOfRangeJob(const double min_velocity, const double max_velocity, const double min_acceleration, const double max_acceleration, const double min_jerk, const double max_jerk) -> void
Definition: entity_base.cpp:687
double traveled_distance_
Definition: entity_base.hpp:362
void updateEntityStatusTimestamp(const double current_time)
Definition: entity_base.cpp:736
std::shared_ptr< CanonicalizedEntityStatus > status_
Definition: entity_base.hpp:355
std::shared_ptr< traffic_simulator::TrafficLightsBase > traffic_lights_
Definition: entity_base.hpp:359
auto isInLanelet() const -> bool
Definition: entity_base.hpp:140
virtual auto getMaxAcceleration() const -> double=0
auto setCanonicalizedStatus(const CanonicalizedEntityStatus &status) -> void
Definition: entity_base.cpp:576
EntityBase(EntityBase &&) noexcept=delete
virtual auto setMapPose(const geometry_msgs::msg::Pose &map_pose) -> void
Definition: entity_base.cpp:681
virtual auto setVelocityLimit(const double) -> void=0
auto as() -> EntityType &
Definition: entity_base.hpp:73
virtual void setTrafficLights(const std::shared_ptr< traffic_simulator::TrafficLightsBase > &traffic_lights)
Definition: entity_base.cpp:658
virtual void setLateralCollisionThreshold(const std::optional< double > &)
Definition: entity_base.hpp:327
EntityBase & operator=(const EntityBase &)=delete
virtual void requestAssignRoute(const std::vector< CanonicalizedLaneletPose > &pose)
Definition: entity_base.hpp:194
virtual auto getRouteLanelets(const double horizon=100.0) -> lanelet::Ids=0
std::optional< double > target_speed_
Definition: entity_base.hpp:368
virtual auto setLinearVelocity(const double linear_velocity) -> void
Definition: entity_base.cpp:648
auto get2DPolygon() const -> std::vector< geometry_msgs::msg::Point >
Definition: entity_base.cpp:72
virtual auto getMaxDeceleration() const -> double=0
virtual auto getGoalPoses() -> std::vector< geometry_msgs::msg::Pose >=0
virtual auto setStatus(const EntityStatus &status) -> void
Definition: entity_base.cpp:586
EntityBase(const std::string &name, const CanonicalizedEntityStatus &entity_status)
Definition: entity_base.cpp:35
virtual auto getObstacle() -> std::optional< traffic_simulator_msgs::msg::Obstacle >=0
virtual auto getDefaultMatchingDistanceForLaneletPoseCalculation() const -> double
Definition: entity_base.cpp:119
Definition: entity_status.hpp:31
Definition: job_list.hpp:26
Definition: lanelet_pose.hpp:35
#define THROW_SEMANTIC_ERROR(...)
Definition: exception.hpp:59
#define DEFINE_GETTER(NAME, TYPE, RETURN_VARIABLE)
Definition: entity_base.hpp:99
Definition: lanelet_wrapper.hpp:43
std::unordered_map< std::pair< std::string, std::string >, double > EuclideanDistancesMap
Definition: entity_base.hpp:50
traffic_simulator_msgs::msg::ActionStatus constructActionStatus(double linear_vel=0, double angular_vel=0, double linear_accel=0, double angular_accel=0)
helper function for constructing action status
Definition: helper.cpp:25
TrajectoryShape
Definition: lane_change.hpp:31
Direction
Definition: lane_change.hpp:29
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
geometry_msgs::msg::Point Point
Definition: lanelet_map.hpp:29
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:70
traffic_simulator_msgs::msg::BoundingBox BoundingBox
Definition: lanelet_wrapper.hpp:65
geometry_msgs::msg::Vector3 Vector3
Definition: lanelet_wrapper.hpp:74
Transition
Definition: speed_change.hpp:26
Definition: operators.hpp:25
Definition: api.hpp:33
traffic_simulator_msgs::msg::EntityType EntityType
Definition: entity_status.hpp:25
traffic_simulator_msgs::msg::EntitySubtype EntitySubtype
Definition: entity_status.hpp:26
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:30
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:24
std::string string
Definition: junit5.hpp:26
Definition: lane_change.hpp:44
parameters for behavior plugin
Definition: lane_change.hpp:75
Definition: route_option.hpp:25
Definition: speed_change.hpp:35