15 #ifndef TRAFFIC_SIMULATOR__ENTITY__ENTITY_BASE_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__ENTITY_BASE_HPP_
18 #include <autoware_control_msgs/msg/control.hpp>
19 #include <autoware_vehicle_msgs/msg/gear_command.hpp>
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>
44 #include <visualization_msgs/msg/marker_array.hpp>
51 class EntityBase :
public std::enable_shared_from_this<EntityBase>
67 auto
is() const ->
bool
69 return dynamic_cast<EntityType const *
>(
this) !=
nullptr;
72 template <
typename EntityType>
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");
83 template <
typename EntityType>
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");
99 #define DEFINE_GETTER(NAME, TYPE, RETURN_VARIABLE) \
105 auto get##NAME() const noexcept->TYPE { return RETURN_VARIABLE; }
147 const lanelet::Id lanelet_id, std::optional<double> tolerance = std::nullopt)
const -> bool;
162 virtual auto
getRouteLanelets(const
double horizon = 100.0) -> lanelet::Ids = 0;
166 virtual auto
onUpdate(const
double current_time, const
double step_time) ->
void;
168 virtual auto
onPostUpdate(const
double current_time, const
double step_time) ->
void;
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
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
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
204 const std::vector<CanonicalizedLaneletPose> &,
const RouteOption &) = 0;
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
216 const std::vector<geometry_msgs::msg::Pose> &,
const RouteOption &) = 0;
251 const bool continuous);
290 const geometry_msgs::msg::
Pose & map_pose,
295 const geometry_msgs::msg::
Pose & reference_pose, const geometry_msgs::msg::
Pose & relative_pose,
300 const geometry_msgs::msg::
Pose & reference_pose,
301 const geometry_msgs::msg::
Point & relative_position,
302 const geometry_msgs::msg::
Vector3 & relative_rpy,
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;
335 auto setTwist(
const geometry_msgs::msg::Twist & twist) -> void;
350 const double tolerance) -> bool;
359 std::shared_ptr<CanonicalizedEntityStatus>
status_;
370 std::unordered_map<std::string, CanonicalizedEntityStatus>
other_status_;
375 std::unique_ptr<traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner>
381 virtual auto requestSpeedChangeWithConstantAcceleration(
383 const bool continuous) -> void;
384 virtual auto requestSpeedChangeWithConstantAcceleration(
388 virtual auto requestSpeedChangeWithTimeConstraint(
391 virtual auto requestSpeedChangeWithTimeConstraint(
394 auto isTargetSpeedReached(
const double target_speed)
const -> bool;
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
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:34
Definition: lane_change.hpp:44
parameters for behavior plugin
Definition: lane_change.hpp:75
Definition: lane_change.hpp:58
Definition: route_option.hpp:25
Definition: speed_change.hpp:35
Definition: speed_change.hpp:51