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 
18 #include <concealer/autoware.hpp>
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 {
38 };
39 
41 {
42 public:
43  const std::unique_ptr<concealer::Autoware> autoware;
44 
45 private:
46  const VehicleModelType vehicle_model_type_;
47 
48  const std::shared_ptr<SimModelInterface> vehicle_model_ptr_;
49 
50  std::optional<double> previous_linear_velocity_, previous_angular_velocity_;
51 
53 
54  const geometry_msgs::msg::Pose initial_pose_;
55 
56  const Eigen::Matrix3d initial_rotation_matrix_;
57 
58  static auto getVehicleModelType() -> VehicleModelType;
59 
60  static auto makeSimulationModel(
61  const VehicleModelType, const double step_time,
62  const traffic_simulator_msgs::msg::VehicleParameters &)
63  -> const std::shared_ptr<SimModelInterface>;
64 
65  const bool consider_acceleration_by_road_slope_;
66 
67  Eigen::Vector3d world_relative_position_;
68 
69 public:
70  const std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils_ptr_;
71 
72  const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters;
73 
74 private:
75  auto calculateEgoPitch() const -> double;
76 
77  auto getCurrentPose(const double pitch_angle) const -> geometry_msgs::msg::Pose;
78 
79  auto getCurrentTwist() const -> geometry_msgs::msg::Twist;
80 
81  auto getCurrentAccel(const double step_time) const -> geometry_msgs::msg::Accel;
82 
83  auto getLinearJerk(double step_time) -> double;
84 
85  auto updatePreviousValues() -> void;
86 
87 public:
88  auto setAutowareStatus() -> void;
89 
90  explicit EgoEntitySimulation(
91  const traffic_simulator_msgs::msg::EntityStatus &,
92  const traffic_simulator_msgs::msg::VehicleParameters &, double,
93  const std::shared_ptr<hdmap_utils::HdMapUtils> &, const rclcpp::Parameter & use_sim_time,
94  const bool consider_acceleration_by_road_slope);
95 
96  auto overwrite(
97  const traffic_simulator_msgs::msg::EntityStatus & status, const double current_time,
98  const double step_time, bool is_npc_logic_started) -> void;
99 
100  auto update(const double current_time, const double step_time, const bool is_npc_logic_started)
101  -> void;
102 
103  auto requestSpeedChange(double value) -> void;
104 
105  auto getStatus() const -> const traffic_simulator_msgs::msg::EntityStatus;
106 
107  auto setStatus(const traffic_simulator_msgs::msg::EntityStatus & status) -> void;
108 
109  auto updateStatus(const double current_time, const double step_time) -> void;
110 };
111 } // namespace vehicle_simulation
112 
113 #endif // TRAFFIC_SIMULATOR__VEHICLE_SIMULATION__EGO_ENTITY_SIMULATION_HPP_
Definition: entity_status.hpp:32
Definition: ego_entity_simulation.hpp:41
auto update(const double current_time, const double step_time, const bool is_npc_logic_started) -> void
Definition: ego_entity_simulation.cpp:287
const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters
Definition: ego_entity_simulation.hpp:72
const std::shared_ptr< hdmap_utils::HdMapUtils > hdmap_utils_ptr_
Definition: ego_entity_simulation.hpp:70
auto updateStatus(const double current_time, const double step_time) -> void
Definition: ego_entity_simulation.cpp:487
auto setAutowareStatus() -> void
Definition: ego_entity_simulation.cpp:177
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:222
auto requestSpeedChange(double value) -> void
Definition: ego_entity_simulation.cpp:190
auto getStatus() const -> const traffic_simulator_msgs::msg::EntityStatus
Definition: ego_entity_simulation.cpp:459
const std::unique_ptr< concealer::Autoware > autoware
Definition: ego_entity_simulation.hpp:43
auto setStatus(const traffic_simulator_msgs::msg::EntityStatus &status) -> void
Definition: ego_entity_simulation.cpp:464
Definition: cache.hpp:46
Definition: cache.hpp:27
Definition: ego_entity_simulation.hpp:29
VehicleModelType
Definition: ego_entity_simulation.hpp:30
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32