15 #ifndef TRAFFIC_SIMULATOR__VEHICLE_SIMULATION__EGO_ENTITY_SIMULATION_HPP_
16 #define TRAFFIC_SIMULATOR__VEHICLE_SIMULATION__EGO_ENTITY_SIMULATION_HPP_
23 #include <traffic_simulator_msgs/msg/entity_status.hpp>
24 #include <traffic_simulator_msgs/msg/polyline_trajectory.hpp>
25 #include <traffic_simulator_msgs/msg/vehicle_parameters.hpp>
43 const std::unique_ptr<concealer::AutowareUniverse>
autoware;
48 const double wheel_base_;
50 const std::shared_ptr<SimModelInterface> vehicle_model_ptr_;
52 std::optional<double> previous_linear_velocity_, previous_angular_velocity_;
58 const Eigen::Matrix3d initial_rotation_matrix_;
62 static auto makeSimulationModel(
64 const traffic_simulator_msgs::msg::VehicleParameters &)
65 ->
const std::shared_ptr<SimModelInterface>;
67 const bool consider_acceleration_by_road_slope_;
69 Eigen::Vector3d world_relative_position_;
77 auto getCurrentPose(const
double pitch_angle = 0.0) 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;
93 const rclcpp::
Parameter & use_sim_time, const
bool consider_acceleration_by_road_slope);
97 const
double step_time,
bool is_npc_logic_started) ->
void;
99 auto
update(const
double current_time, const
double step_time, const
bool is_npc_logic_started)
108 auto
updateStatus(const
double current_time, const
double step_time) ->
void;
Definition: entity_status.hpp:31
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:297
const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters
Definition: ego_entity_simulation.hpp:72
auto updateStatus(const double current_time, const double step_time) -> void
Definition: ego_entity_simulation.cpp:461
auto setAutowareStatus() -> void
Definition: ego_entity_simulation.cpp:172
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 calculateAccelerationBySlope() const -> double
Definition: ego_entity_simulation.cpp:362
auto requestSpeedChange(double value) -> void
Definition: ego_entity_simulation.cpp:186
auto getStatus() const -> const traffic_simulator_msgs::msg::EntityStatus
Definition: ego_entity_simulation.cpp:434
const std::unique_ptr< concealer::AutowareUniverse > autoware
Definition: ego_entity_simulation.hpp:43
auto setStatus(const traffic_simulator_msgs::msg::EntityStatus &status) -> void
Definition: ego_entity_simulation.cpp:439
traffic_simulator::lane_change::Parameter Parameter
Definition: lane_change.hpp:27
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:70
Definition: operators.hpp:25
Definition: ego_entity_simulation.hpp:28
VehicleModelType
Definition: ego_entity_simulation.hpp:29
@ DELAY_STEER_MAP_ACC_GEARED
@ DELAY_STEER_ACC_GEARED_WO_FALL_GUARD
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32