scenario_simulator_v2 C++ API
ego_entity_simulation.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__VEHICLE_SIMULATION__EGO_ENTITY_SIMULATION_HPP_
16 #define TRAFFIC_SIMULATOR__VEHICLE_SIMULATION__EGO_ENTITY_SIMULATION_HPP_
17 
19 #include <memory>
24 #include <traffic_simulator_msgs/msg/entity_status.hpp>
25 #include <traffic_simulator_msgs/msg/polyline_trajectory.hpp>
26 #include <traffic_simulator_msgs/msg/vehicle_parameters.hpp>
27 
29 {
30 enum class VehicleModelType {
39 };
40 
42 {
43 public:
44  const std::unique_ptr<concealer::AutowareUniverse> autoware;
45 
46 private:
47  const VehicleModelType vehicle_model_type_;
48 
49  const std::shared_ptr<SimModelInterface> vehicle_model_ptr_;
50 
51  std::optional<double> previous_linear_velocity_, previous_angular_velocity_;
52 
54 
55  const geometry_msgs::msg::Pose initial_pose_;
56 
57  const Eigen::Matrix3d initial_rotation_matrix_;
58 
59  static auto getVehicleModelType() -> VehicleModelType;
60 
61  static auto makeSimulationModel(
62  const VehicleModelType, const double step_time,
63  const traffic_simulator_msgs::msg::VehicleParameters &)
64  -> const std::shared_ptr<SimModelInterface>;
65 
66  const bool consider_acceleration_by_road_slope_;
67 
68  Eigen::Vector3d world_relative_position_;
69 
70 public:
71  const std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils_ptr_;
72 
73  const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters;
74 
75  auto calculateAccelerationBySlope() const -> double;
76 
77 private:
78  auto getCurrentPose(const double pitch_angle) const -> geometry_msgs::msg::Pose;
79 
80  auto getCurrentTwist() const -> geometry_msgs::msg::Twist;
81 
82  auto getCurrentAccel(const double step_time) const -> geometry_msgs::msg::Accel;
83 
84  auto getLinearJerk(double step_time) -> double;
85 
86  auto updatePreviousValues() -> void;
87 
88 public:
89  auto setAutowareStatus() -> void;
90 
91  explicit EgoEntitySimulation(
92  const traffic_simulator_msgs::msg::EntityStatus &,
93  const traffic_simulator_msgs::msg::VehicleParameters &, double,
94  const std::shared_ptr<hdmap_utils::HdMapUtils> &, const rclcpp::Parameter & use_sim_time,
95  const bool consider_acceleration_by_road_slope);
96 
97  auto overwrite(
98  const traffic_simulator_msgs::msg::EntityStatus & status, const double current_time,
99  const double step_time, bool is_npc_logic_started) -> void;
100 
101  auto update(const double current_time, const double step_time, const bool is_npc_logic_started)
102  -> void;
103 
104  auto requestSpeedChange(double value) -> void;
105 
106  auto getStatus() const -> const traffic_simulator_msgs::msg::EntityStatus;
107 
108  auto setStatus(const traffic_simulator_msgs::msg::EntityStatus & status) -> void;
109 
110  auto updateStatus(const double current_time, const double step_time) -> void;
111 };
112 } // namespace vehicle_simulation
113 
114 #endif // TRAFFIC_SIMULATOR__VEHICLE_SIMULATION__EGO_ENTITY_SIMULATION_HPP_
Definition: entity_status.hpp:32
Definition: ego_entity_simulation.hpp:42
auto update(const double current_time, const double step_time, const bool is_npc_logic_started) -> void
Definition: ego_entity_simulation.cpp:286
const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters
Definition: ego_entity_simulation.hpp:73
const std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils_ptr_
Definition: ego_entity_simulation.hpp:71
auto updateStatus(const double current_time, const double step_time) -> void
Definition: ego_entity_simulation.cpp:450
auto setAutowareStatus() -> void
Definition: ego_entity_simulation.cpp:171
auto overwrite(const traffic_simulator_msgs::msg::EntityStatus &status, const double current_time, const double step_time, bool is_npc_logic_started) -> void
Definition: ego_entity_simulation.cpp:220
auto calculateAccelerationBySlope() const -> double
Definition: ego_entity_simulation.cpp:351
auto requestSpeedChange(double value) -> void
Definition: ego_entity_simulation.cpp:184
auto getStatus() const -> const traffic_simulator_msgs::msg::EntityStatus
Definition: ego_entity_simulation.cpp:423
const std::unique_ptr< concealer::AutowareUniverse > autoware
Definition: ego_entity_simulation.hpp:44
auto setStatus(const traffic_simulator_msgs::msg::EntityStatus &status) -> void
Definition: ego_entity_simulation.cpp:428
Definition: cache.hpp:28
Definition: lanelet_wrapper.hpp:40
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:66
Definition: ego_entity_simulation.hpp:29
VehicleModelType
Definition: ego_entity_simulation.hpp:30
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32