15 #ifndef TRAFFIC_SIMULATOR__ENTITY__EGO_ENTITY_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__EGO_ENTITY_HPP_
19 #include <boost/filesystem.hpp>
27 #include <traffic_simulator_msgs/msg/entity_type.hpp>
36 bool is_controlled_by_simulator_{
false};
37 std::optional<double> target_speed_;
38 traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter_;
39 std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> polyline_trajectory_;
46 const std::shared_ptr<hdmap_utils::HdMapUtils> &,
47 const traffic_simulator_msgs::msg::VehicleParameters &,
const Configuration &,
48 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &);
65 -> const traffic_simulator_msgs::msg::DynamicConstraints & override;
73 auto
getObstacle() ->
std::optional<traffic_simulator_msgs::msg::Obstacle> override;
77 auto
getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override;
81 void onUpdate(
double current_time,
double step_time) override;
92 const
std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> &) ->
void override;
99 const
double, const speed_change::
Transition, const speed_change::Constraint,
100 const
bool continuous) ->
void override;
103 const speed_change::RelativeTargetSpeed &, const speed_change::
Transition,
104 const speed_change::Constraint, const
bool continuous) ->
void override;
116 is_controlled_by_simulator_ = state;
131 template <
typename ParameterType>
135 return declare_parameter<ParameterType>(
name, default_value);
138 template <
typename... Ts>
143 "You cannot set entity status to the ego vehicle named ", std::quoted(
status_->getName()),
144 " after starting scenario.");
Definition: ego_entity.hpp:35
auto isEngageable() const -> bool
Definition: ego_entity.cpp:79
auto getObstacle() -> std::optional< traffic_simulator_msgs::msg::Obstacle > override
Definition: ego_entity.cpp:136
auto setMapPose(const geometry_msgs::msg::Pose &map_pose) -> void override
Definition: ego_entity.cpp:325
void requestAssignRoute(const std::vector< CanonicalizedLaneletPose > &) override
Definition: ego_entity.cpp:205
auto isEngaged() const -> bool
Definition: ego_entity.cpp:77
void requestAcquirePosition(const CanonicalizedLaneletPose &) override
Definition: ego_entity.cpp:195
auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override
Definition: ego_entity.cpp:157
auto getEntityStatus(const double, const double) const -> const CanonicalizedEntityStatus
auto getCurrentPose() const -> const geometry_msgs::msg::Pose &
Definition: ego_entity.cpp:152
auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
Definition: ego_entity.cpp:290
~EgoEntity() override=default
auto requestClearRoute() -> void
Definition: ego_entity.cpp:279
auto setParameter(const std::string &name, const ParameterType &default_value={}) -> ParameterType
Definition: ego_entity.hpp:132
void onUpdate(double current_time, double step_time) override
Definition: ego_entity.cpp:168
auto setControlledBySimulator(bool state) -> void override
Definition: ego_entity.hpp:114
auto engage() -> void
Definition: ego_entity.cpp:75
auto getEntityTypename() const -> const std::string &override
Definition: ego_entity.cpp:130
auto requestReplanRoute(const std::vector< geometry_msgs::msg::PoseStamped > &route) -> void
Definition: ego_entity.cpp:281
auto requestFollowTrajectory(const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void override
Definition: ego_entity.cpp:239
auto setVelocityLimit(double) -> void override
Definition: ego_entity.cpp:319
auto operator=(EgoEntity &&) -> EgoEntity &=delete
auto requestLaneChange(const lanelet::Id) -> void override
Definition: ego_entity.cpp:247
auto getCurrentAction() const -> std::string override
Definition: ego_entity.cpp:120
auto sendCooperateCommand(const std::string &module_name, const std::string &command) -> void
Definition: ego_entity.cpp:81
auto operator=(const EgoEntity &) -> EgoEntity &=delete
auto getRouteLanelets(double horizon=100) -> lanelet::Ids override
Definition: ego_entity.cpp:141
EgoEntity(const EgoEntity &)=delete
auto requestAutoModeForCooperation(const std::string &module_name, bool enable) -> void
Definition: ego_entity.cpp:87
auto setStatus(Ts &&... xs) -> void
Definition: ego_entity.hpp:139
auto getTurnIndicatorsCommandName() const -> std::string
Definition: ego_entity.cpp:104
auto setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &) -> void override
Definition: ego_entity.cpp:296
auto updateFieldOperatorApplication() -> void
Definition: ego_entity.cpp:162
auto getMinimumRiskManeuverStateName() const -> std::string
Definition: ego_entity.cpp:97
EgoEntity(EgoEntity &&)=delete
auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter override
Definition: ego_entity.cpp:122
auto requestSpeedChange(const double, const speed_change::Transition, const speed_change::Constraint, const bool continuous) -> void override
Definition: ego_entity.cpp:263
auto getEmergencyStateName() const -> std::string
Definition: ego_entity.cpp:102
auto isControlledBySimulator() const -> bool override
Definition: ego_entity.cpp:237
auto getMinimumRiskManeuverBehaviorName() const -> std::string
Definition: ego_entity.cpp:92
const std::string name
Definition: entity_base.hpp:285
std::shared_ptr< CanonicalizedEntityStatus > status_
Definition: entity_base.hpp:290
virtual auto setStatus(const EntityStatus &status) -> void
Definition: entity_base.cpp:588
Definition: vehicle_entity.hpp:37
Definition: entity_status.hpp:32
Definition: lanelet_pose.hpp:35
#define THROW_SEMANTIC_ERROR(...)
Definition: exception.hpp:59
Definition: lanelet_wrapper.hpp:39
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:65
geometry_msgs::msg::PoseStamped PoseStamped
Definition: lanelet_wrapper.hpp:66
auto route(Ts &&... xs)
Definition: route.hpp:30
Transition
Definition: speed_change.hpp:26
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: field_operator_application.hpp:59
Definition: configuration.hpp:31
Definition: speed_change.hpp:51