diff --git a/external/concealer/include/concealer/field_operator_application.hpp b/external/concealer/include/concealer/field_operator_application.hpp index d5be067e0b0..13026c8e5cb 100644 --- a/external/concealer/include/concealer/field_operator_application.hpp +++ b/external/concealer/include/concealer/field_operator_application.hpp @@ -31,7 +31,6 @@ #include #include #include -#include #include #include #include @@ -136,13 +135,7 @@ struct FieldOperatorApplication : public rclcpp::Node, */ TaskQueue task_queue; - CONCEALER_PUBLIC explicit FieldOperatorApplication(const pid_t = 0); - - template - CONCEALER_PUBLIC explicit FieldOperatorApplication(Ts &&... xs) - : FieldOperatorApplication(ros2_launch(std::forward(xs)...)) - { - } + CONCEALER_PUBLIC explicit FieldOperatorApplication(const pid_t); ~FieldOperatorApplication(); diff --git a/simulation/traffic_simulator/include/traffic_simulator/entity/ego_entity.hpp b/simulation/traffic_simulator/include/traffic_simulator/entity/ego_entity.hpp index 91cab0f7f97..5580e106e39 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/entity/ego_entity.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/entity/ego_entity.hpp @@ -35,10 +35,6 @@ class EgoEntity : public VehicleEntity { const std::unique_ptr field_operator_application; - static auto makeFieldOperatorApplication( - const Configuration &, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &) - -> std::unique_ptr; - bool is_controlled_by_simulator_{false}; std::optional target_speed_; traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter_; diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index e4f9560c180..194ef8287d1 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -14,6 +14,7 @@ #include #include +#include #include #include #include @@ -32,7 +33,7 @@ namespace traffic_simulator { namespace entity { -auto EgoEntity::makeFieldOperatorApplication( +auto makeFieldOperatorApplication( const Configuration & configuration, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters) -> std::unique_ptr @@ -56,11 +57,12 @@ auto EgoEntity::makeFieldOperatorApplication( parameters.push_back("localization_sim_mode:=" + std::string(getParameter(node_parameters, "simulate_localization") ? "api" : "pose_twist_estimator")); // clang-format on - return getParameter(node_parameters, "launch_autoware", true) - ? std::make_unique( - getParameter(node_parameters, "autoware_launch_package"), - getParameter(node_parameters, "autoware_launch_file"), parameters) - : std::make_unique(); + return std::make_unique( + getParameter(node_parameters, "launch_autoware", true) + ? concealer::ros2_launch( + getParameter(node_parameters, "autoware_launch_package"), + getParameter(node_parameters, "autoware_launch_file"), parameters) + : 0); } else { throw common::SemanticError( "Unexpected architecture_type ", std::quoted(architecture_type), " was given."); @@ -113,9 +115,7 @@ auto EgoEntity::getRouteLanelets(double /*unused horizon*/) -> lanelet::Ids { lanelet::Ids ids{}; - if (const auto universe = - dynamic_cast(field_operator_application.get()); - universe) { + if (const auto universe = field_operator_application.get(); universe) { for (const auto & point : universe->getPathWithLaneId().points) { ids += point.lane_ids; }