15 #ifndef TRAFFIC_SIMULATOR__VEHICLE_SIMULATION__EGO_ENTITY_SIMULATION_HPP_
16 #define TRAFFIC_SIMULATOR__VEHICLE_SIMULATION__EGO_ENTITY_SIMULATION_HPP_
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>
43 const std::unique_ptr<concealer::Autoware>
autoware;
48 const std::shared_ptr<SimModelInterface> vehicle_model_ptr_;
50 std::optional<double> previous_linear_velocity_, previous_angular_velocity_;
54 const geometry_msgs::msg::Pose initial_pose_;
56 const Eigen::Matrix3d initial_rotation_matrix_;
60 static auto makeSimulationModel(
62 const traffic_simulator_msgs::msg::VehicleParameters &)
63 ->
const std::shared_ptr<SimModelInterface>;
65 const bool consider_acceleration_by_road_slope_;
67 Eigen::Vector3d world_relative_position_;
75 auto calculateEgoPitch() const ->
double;
77 auto getCurrentPose(const
double pitch_angle) const -> geometry_msgs::msg::Pose;
79 auto getCurrentTwist() const -> geometry_msgs::msg::Twist;
81 auto getCurrentAccel(const
double step_time) const -> geometry_msgs::msg::Accel;
83 auto getLinearJerk(
double step_time) ->
double;
85 auto updatePreviousValues() ->
void;
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);
97 const traffic_simulator_msgs::msg::
EntityStatus & status, const
double current_time,
98 const
double step_time,
bool is_npc_logic_started) ->
void;
100 auto
update(const
double current_time, const
double step_time, const
bool is_npc_logic_started)
109 auto
updateStatus(const
double current_time, const
double step_time) ->
void;
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: ego_entity_simulation.hpp:29
VehicleModelType
Definition: ego_entity_simulation.hpp:30
@ DELAY_STEER_MAP_ACC_GEARED
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32