scenario_simulator_v2 C++ API
ego_entity.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__EGO_ENTITY_HPP_
16 #define TRAFFIC_SIMULATOR__ENTITY__EGO_ENTITY_HPP_
17 
18 #include <algorithm>
19 #include <boost/filesystem.hpp>
21 #include <memory>
22 #include <optional>
23 #include <string>
27 #include <traffic_simulator_msgs/msg/entity_type.hpp>
28 #include <vector>
29 
30 namespace traffic_simulator
31 {
32 namespace entity
33 {
35 {
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_;
40 
41 public:
42  explicit EgoEntity() = delete;
43 
44  explicit EgoEntity(
46  const std::shared_ptr<hdmap_utils::HdMapUtils> &,
47  const traffic_simulator_msgs::msg::VehicleParameters &, const Configuration &,
48  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &);
49 
50  explicit EgoEntity(EgoEntity &&) = delete;
51 
52  explicit EgoEntity(const EgoEntity &) = delete;
53 
54  ~EgoEntity() override = default;
55 
56  auto operator=(EgoEntity &&) -> EgoEntity & = delete;
57 
58  auto operator=(const EgoEntity &) -> EgoEntity & = delete;
59 
60  auto getCurrentAction() const -> std::string override;
61 
62  auto getCurrentPose() const -> const geometry_msgs::msg::Pose &;
63 
64  auto getDefaultDynamicConstraints() const
65  -> const traffic_simulator_msgs::msg::DynamicConstraints & override;
66 
67  auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter override;
68 
69  auto getEntityStatus(const double, const double) const -> const CanonicalizedEntityStatus;
70 
71  auto getEntityTypename() const -> const std::string & override;
72 
73  auto getObstacle() -> std::optional<traffic_simulator_msgs::msg::Obstacle> override;
74 
75  auto getRouteLanelets(double horizon = 100) -> lanelet::Ids override;
76 
77  auto getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray override;
78 
79  auto updateFieldOperatorApplication() -> void;
80 
81  void onUpdate(double current_time, double step_time) override;
82 
83  void requestAcquirePosition(const CanonicalizedLaneletPose &) override;
84 
85  void requestAcquirePosition(const geometry_msgs::msg::Pose & map_pose) override;
86 
87  void requestAssignRoute(const std::vector<CanonicalizedLaneletPose> &) override;
88 
89  void requestAssignRoute(const std::vector<geometry_msgs::msg::Pose> &) override;
90 
92  const std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> &) -> void override;
93 
94  auto requestLaneChange(const lanelet::Id) -> void override;
95 
96  auto requestLaneChange(const lane_change::Parameter &) -> void override;
97 
98  auto requestSpeedChange(
99  const double, const speed_change::Transition, const speed_change::Constraint,
100  const bool continuous) -> void override;
101 
102  auto requestSpeedChange(
103  const speed_change::RelativeTargetSpeed &, const speed_change::Transition,
104  const speed_change::Constraint, const bool continuous) -> void override;
105 
106  auto requestClearRoute() -> void;
107 
108  auto requestReplanRoute(const std::vector<geometry_msgs::msg::PoseStamped> & route) -> void;
109 
110  auto requestAutoModeForCooperation(const std::string & module_name, bool enable) -> void;
111 
112  auto isControlledBySimulator() const -> bool override;
113 
114  auto setControlledBySimulator(bool state) -> void override
115  {
116  is_controlled_by_simulator_ = state;
117  }
118 
119  auto setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &)
120  -> void override;
121 
122  void requestSpeedChange(double, bool continuous) override;
123 
124  void requestSpeedChange(
125  const speed_change::RelativeTargetSpeed & target_speed, bool continuous) override;
126 
127  auto setVelocityLimit(double) -> void override;
128 
129  auto setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void override;
130 
131  template <typename ParameterType>
132  auto setParameter(const std::string & name, const ParameterType & default_value = {})
133  -> ParameterType
134  {
135  return declare_parameter<ParameterType>(name, default_value);
136  }
137 
138  template <typename... Ts>
139  auto setStatus(Ts &&... xs) -> void
140  {
141  if (status_->getTime() > 0 && not isControlledBySimulator()) {
143  "You cannot set entity status to the ego vehicle named ", std::quoted(status_->getName()),
144  " after starting scenario.");
145  } else {
146  EntityBase::setStatus(std::forward<decltype(xs)>(xs)...);
147  }
148  }
149 
150  auto engage() -> void;
151  auto isEngaged() const -> bool;
152  auto isEngageable() const -> bool;
153  auto sendCooperateCommand(const std::string & module_name, const std::string & command) -> void;
154  auto getMinimumRiskManeuverBehaviorName() const -> std::string;
155  auto getMinimumRiskManeuverStateName() const -> std::string;
156  auto getEmergencyStateName() const -> std::string;
157  auto getTurnIndicatorsCommandName() const -> std::string;
158 };
159 } // namespace entity
160 } // namespace traffic_simulator
161 #endif // TRAFFIC_SIMULATOR__ENTITY__EGO_ENTITY_HPP_
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
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
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: api.hpp:48
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: field_operator_application.hpp:59
Definition: configuration.hpp:31