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>
55 const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr);
66 #define DEFINE_GETTER(NAME, TYPE, RETURN_VARIABLE) \
72 auto get##NAME() const noexcept->TYPE { return RETURN_VARIABLE; }
90 #define DEFINE_CHECK_FUNCTION(FUNCTION_NAME, BOOL_VARIABLE) \
94 auto FUNCTION_NAME() const->bool { return BOOL_VARIABLE; }
98 #undef DEFINE_CHECK_FUNCTION
104 virtual auto
getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter = 0;
107 -> const traffic_simulator_msgs::msg::DynamicConstraints & = 0;
124 virtual auto
getObstacle() ->
std::optional<traffic_simulator_msgs::msg::Obstacle> = 0;
126 virtual auto
getRouteLanelets(const
double horizon = 100.0) -> lanelet::Ids = 0;
128 virtual auto
getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray = 0;
130 virtual auto
onUpdate(const
double current_time, const
double step_time) ->
void;
132 virtual auto
onPostUpdate(const
double current_time, const
double step_time) ->
void;
175 const bool continuous);
195 const
std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> & ) ->
void;
208 const traffic_simulator_msgs::msg::DynamicConstraints & constraints);
229 const
double min_velocity, const
double max_velocity, const
double min_acceleration,
230 const
double max_acceleration, const
double min_jerk, const
double max_jerk) ->
void;
234 virtual auto
setMapPose(const geometry_msgs::msg::Pose & map_pose) ->
void;
236 auto
setTwist(const geometry_msgs::msg::Twist & twist) ->
void;
249 const geometry_msgs::msg::Pose & target_pose, const
double tolerance) const;
254 bool reachPosition(const
std::
string & target_name, const
double tolerance) const;
259 const
double tolerance) ->
bool;
287 virtual auto requestSpeedChangeWithConstantAcceleration(
288 const
double target_speed, const speed_change::
Transition, const
double acceleration,
289 const
bool continuous) ->
void;
290 virtual auto requestSpeedChangeWithConstantAcceleration(
291 const speed_change::RelativeTargetSpeed & target_speed,
292 const speed_change::
Transition transition, const
double acceleration, const
bool continuous)
294 virtual auto requestSpeedChangeWithTimeConstraint(
295 const
double target_speed, const speed_change::
Transition, const
double acceleration_time)
297 virtual auto requestSpeedChangeWithTimeConstraint(
298 const speed_change::RelativeTargetSpeed & target_speed,
299 const speed_change::
Transition transition, const
double time) ->
void;
300 auto isTargetSpeedReached(const
double target_speed) const ->
bool;
301 auto isTargetSpeedReached(const speed_change::RelativeTargetSpeed & target_speed) const
Definition: traffic_lights_base.hpp:39
Definition: entity_base.hpp:51
virtual auto setStatus(const EntityStatus &status, const lanelet::Ids &lanelet_ids) -> void
Definition: entity_base.cpp:546
auto setTwist(const geometry_msgs::msg::Twist &twist) -> void
Definition: entity_base.cpp:578
virtual auto setLinearAcceleration(const double linear_acceleration) -> void
Definition: entity_base.cpp:567
virtual void setDecelerationLimit(const double deceleration)=0
CanonicalizedEntityStatus status_before_update_
Definition: entity_base.hpp:262
auto setLinearJerk(const double liner_jerk) -> void
Definition: entity_base.cpp:588
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:519
virtual ~EntityBase()=default
virtual void setAccelerationLimit(const double acceleration)=0
double stand_still_duration_
Definition: entity_base.hpp:267
virtual auto onUpdate(const double current_time, const double step_time) -> void
Definition: entity_base.cpp:122
virtual void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &)=0
void stopAtCurrentPosition()
Definition: entity_base.cpp:643
traffic_simulator::job::JobList job_list_
Definition: entity_base.hpp:275
void setOtherStatus(const std::unordered_map< std::string, CanonicalizedEntityStatus > &status)
Definition: entity_base.cpp:539
virtual auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints &=0
virtual void requestAcquirePosition(const CanonicalizedLaneletPose &)=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:681
const std::string name
Definition: entity_base.hpp:255
virtual auto getGoalPoses() -> std::vector< CanonicalizedLaneletPose >=0
void resetDynamicConstraints()
Definition: entity_base.cpp:137
virtual void requestClearRoute()
Definition: entity_base.hpp:176
virtual void requestSpeedChange(const double target_speed, const speed_change::Transition transition, const speed_change::Constraint constraint, const bool continuous)
Definition: entity_base.cpp:293
std::unordered_map< std::string, CanonicalizedEntityStatus > other_status_
Definition: entity_base.hpp:272
virtual auto getCurrentAction() const -> std::string=0
virtual auto isControlledBySimulator() const -> bool
Definition: entity_base.cpp:511
virtual auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter=0
double step_time_
Definition: entity_base.hpp:270
std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils_ptr_
Definition: entity_base.hpp:264
auto getLinearJerk() const noexcept -> double
Get LinearJerk of the entity.
Definition: entity_base.hpp:78
virtual void appendDebugMarker(visualization_msgs::msg::MarkerArray &)
Definition: entity_base.cpp:69
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:79
std::unique_ptr< traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner > speed_planner_
Definition: entity_base.hpp:278
virtual void requestWalkStraight()
Definition: entity_base.cpp:526
virtual auto onPostUpdate(const double current_time, const double step_time) -> void
Definition: entity_base.cpp:132
EntityBase(const std::string &name, const CanonicalizedEntityStatus &entity_status, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr)
Definition: entity_base.cpp:33
auto setAcceleration(const geometry_msgs::msg::Accel &accel) -> void
Definition: entity_base.cpp:583
auto getCanonicalizedLaneletPose() const -> std::optional< CanonicalizedLaneletPose >
Definition: entity_base.cpp:86
bool reachPosition(const geometry_msgs::msg::Pose &target_pose, const double tolerance) const
Definition: entity_base.cpp:660
void setDynamicConstraints(const traffic_simulator_msgs::msg::DynamicConstraints &constraints)
Definition: entity_base.cpp:531
virtual auto getEntityTypename() const -> const std::string &=0
auto setAction(const std::string &action) -> void
Definition: entity_base.cpp:593
auto getMapPose() const noexcept -> const geometry_msgs::msg::Pose &
Get MapPose of the entity.
Definition: entity_base.hpp:79
virtual auto setControlledBySimulator(const bool) -> void
Definition: entity_base.cpp:513
auto laneMatchingSucceed() const -> bool
Definition: entity_base.hpp:90
double prev_job_duration_
Definition: entity_base.hpp:269
bool verbose
Definition: entity_base.hpp:257
virtual void requestAssignRoute(const std::vector< CanonicalizedLaneletPose > &)=0
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:601
double traveled_distance_
Definition: entity_base.hpp:268
void updateEntityStatusTimestamp(const double current_time)
Definition: entity_base.cpp:650
std::shared_ptr< CanonicalizedEntityStatus > status_
Definition: entity_base.hpp:260
std::shared_ptr< traffic_simulator::TrafficLightsBase > traffic_lights_
Definition: entity_base.hpp:265
virtual auto getMaxAcceleration() const -> double=0
auto setCanonicalizedStatus(const CanonicalizedEntityStatus &status) -> void
Definition: entity_base.cpp:557
virtual auto setMapPose(const geometry_msgs::msg::Pose &map_pose) -> void
Definition: entity_base.cpp:595
virtual auto setVelocityLimit(const double) -> void=0
virtual auto asFieldOperatorApplication() const -> concealer::FieldOperatorApplication &
Definition: entity_base.cpp:71
virtual void setTrafficLights(const std::shared_ptr< traffic_simulator::TrafficLightsBase > &traffic_lights)
Definition: entity_base.cpp:572
virtual void requestLaneChange(const lanelet::Id)
Definition: entity_base.hpp:138
virtual auto getRouteLanelets(const double horizon=100.0) -> lanelet::Ids=0
std::optional< double > target_speed_
Definition: entity_base.hpp:274
virtual auto setLinearVelocity(const double linear_velocity) -> void
Definition: entity_base.cpp:562
auto get2DPolygon() const -> std::vector< geometry_msgs::msg::Point >
Definition: entity_base.cpp:81
virtual auto getMaxDeceleration() const -> double=0
virtual auto getObstacle() -> std::optional< traffic_simulator_msgs::msg::Obstacle >=0
virtual auto getDefaultMatchingDistanceForLaneletPoseCalculation() const -> double
Definition: entity_base.cpp:105
Definition: entity_status.hpp:32
Definition: lanelet_pose.hpp:27
#define DEFINE_GETTER(NAME, TYPE, RETURN_VARIABLE)
Definition: entity_base.hpp:66
#define DEFINE_CHECK_FUNCTION(FUNCTION_NAME, BOOL_VARIABLE)
Definition: entity_base.hpp:86
Definition: autoware_universe.hpp:40
TrajectoryShape
Definition: lane_change.hpp:31
Transition
Definition: speed_change.hpp:26
traffic_simulator_msgs::msg::EntityType EntityType
Definition: entity_status.hpp:26
traffic_simulator_msgs::msg::EntitySubtype EntitySubtype
Definition: entity_status.hpp:27
traffic_simulator_msgs::msg::EntityStatus EntityStatus
Definition: entity_status.hpp:25
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: speed_change.hpp:35
Definition: speed_change.hpp:51