15 #ifndef TRAFFIC_SIMULATOR__ENTITY__EGO_ENTITY_HPP_ 
   16 #define TRAFFIC_SIMULATOR__ENTITY__EGO_ENTITY_HPP_ 
   19 #include <boost/filesystem.hpp> 
   21 #include <get_parameter/get_parameter.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 &);
 
   81   void onUpdate(
double current_time, 
double step_time) override;
 
  111     const 
double, const speed_change::
Transition, const speed_change::Constraint,
 
  112     const 
bool continuous) -> 
void override;
 
  115     const speed_change::RelativeTargetSpeed &, const speed_change::
Transition,
 
  116     const speed_change::Constraint, const 
bool continuous) -> 
void override;
 
  122     const 
bool allow_goal_modification = false) -> 
void;
 
  130     is_controlled_by_simulator_ = state;
 
  145   template <
typename ParameterType>
 
  149     return declare_parameter<ParameterType>(
name, default_value);
 
  152   template <
typename... Ts>
 
  157         "You cannot set entity status to the ego vehicle named ", std::quoted(
status_->getName()),
 
  158         " after starting scenario.");
 
Definition: ego_entity.hpp:35
 
auto isEngageable() const -> bool
Definition: ego_entity.cpp:90
 
auto requestReplanRoute(const std::vector< geometry_msgs::msg::PoseStamped > &route, const bool allow_goal_modification=false) -> void
Definition: ego_entity.cpp:399
 
auto getObstacle() -> std::optional< traffic_simulator_msgs::msg::Obstacle > override
Definition: ego_entity.cpp:147
 
auto setMapPose(const geometry_msgs::msg::Pose &map_pose) -> void override
Definition: ego_entity.cpp:460
 
void requestAssignRoute(const std::vector< CanonicalizedLaneletPose > &) override
Definition: ego_entity.cpp:232
 
auto isEngaged() const -> bool
Definition: ego_entity.cpp:88
 
void requestAcquirePosition(const CanonicalizedLaneletPose &) override
Definition: ego_entity.cpp:206
 
auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override
Definition: ego_entity.cpp:168
 
auto getEntityStatus(const double, const double) const -> const CanonicalizedEntityStatus
 
auto getCurrentPose() const -> const geometry_msgs::msg::Pose &
Definition: ego_entity.cpp:163
 
auto getDefaultDynamicConstraints() const -> const traffic_simulator_msgs::msg::DynamicConstraints &override
Definition: ego_entity.cpp:425
 
~EgoEntity() override=default
 
auto requestClearRoute() -> void
Definition: ego_entity.cpp:397
 
auto setParameter(const std::string &name, const ParameterType &default_value={}) -> ParameterType
Definition: ego_entity.hpp:146
 
void onUpdate(double current_time, double step_time) override
Definition: ego_entity.cpp:180
 
auto setControlledBySimulator(bool state) -> void override
Definition: ego_entity.hpp:128
 
auto engage() -> void
Definition: ego_entity.cpp:86
 
auto getEntityTypename() const -> const std::string &override
Definition: ego_entity.cpp:141
 
auto requestFollowTrajectory(const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &) -> void override
Definition: ego_entity.cpp:357
 
auto setVelocityLimit(double) -> void override
Definition: ego_entity.cpp:454
 
auto operator=(EgoEntity &&) -> EgoEntity &=delete
 
auto requestLaneChange(const lanelet::Id) -> void override
Definition: ego_entity.cpp:365
 
auto getCurrentAction() const -> std::string override
Definition: ego_entity.cpp:131
 
auto sendCooperateCommand(const std::string &module_name, const std::string &command) -> void
Definition: ego_entity.cpp:92
 
auto operator=(const EgoEntity &) -> EgoEntity &=delete
 
auto getRouteLanelets(double horizon=100) -> lanelet::Ids override
Definition: ego_entity.cpp:152
 
auto updateFieldOperatorApplication() -> void
Definition: ego_entity.cpp:178
 
EgoEntity(const EgoEntity &)=delete
 
auto requestAutoModeForCooperation(const std::string &module_name, bool enable) -> void
Definition: ego_entity.cpp:98
 
auto setStatus(Ts &&... xs) -> void
Definition: ego_entity.hpp:153
 
auto getTurnIndicatorsCommandName() const -> std::string
Definition: ego_entity.cpp:115
 
auto setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &) -> void override
Definition: ego_entity.cpp:431
 
auto getMinimumRiskManeuverStateName() const -> std::string
Definition: ego_entity.cpp:108
 
EgoEntity(EgoEntity &&)=delete
 
auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter override
Definition: ego_entity.cpp:133
 
auto requestSpeedChange(const double, const speed_change::Transition, const speed_change::Constraint, const bool continuous) -> void override
Definition: ego_entity.cpp:381
 
auto getEmergencyStateName() const -> std::string
Definition: ego_entity.cpp:113
 
auto isControlledBySimulator() const -> bool override
Definition: ego_entity.cpp:355
 
auto getMinimumRiskManeuverBehaviorName() const -> std::string
Definition: ego_entity.cpp:103
 
const std::string name
Definition: entity_base.hpp:351
 
std::shared_ptr< CanonicalizedEntityStatus > status_
Definition: entity_base.hpp:358
 
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:28
 
#define THROW_SEMANTIC_ERROR(...)
Definition: exception.hpp:59
 
Definition: lanelet_wrapper.hpp:40
 
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
 
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:66
 
geometry_msgs::msg::PoseStamped PoseStamped
Definition: lanelet_wrapper.hpp:67
 
auto route(Ts &&... xs)
Definition: route.hpp:30
 
Transition
Definition: speed_change.hpp:26
 
Definition: operators.hpp:25
 
Definition: junit5.hpp:25
 
std::string string
Definition: junit5.hpp:26
 
Definition: field_operator_application.hpp:53
 
void RouteOption
Definition: field_operator_application.hpp:176
 
Definition: configuration.hpp:31
 
Definition: speed_change.hpp:51