Skip to content

Commit

Permalink
Remove static member function EgoEntity::makeFieldOperatorApplication
Browse files Browse the repository at this point in the history
Signed-off-by: yamacir-kit <[email protected]>
  • Loading branch information
yamacir-kit committed Dec 19, 2024
1 parent 71094df commit 544fd7b
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
#include <autoware_vehicle_msgs/msg/gear_command.hpp>
#include <autoware_vehicle_msgs/msg/turn_indicators_command.hpp>
#include <concealer/autoware_universe.hpp>
#include <concealer/launch.hpp>
#include <concealer/publisher.hpp>
#include <concealer/service.hpp>
#include <concealer/subscriber.hpp>
Expand Down Expand Up @@ -136,13 +135,7 @@ struct FieldOperatorApplication : public rclcpp::Node,
*/
TaskQueue task_queue;

CONCEALER_PUBLIC explicit FieldOperatorApplication(const pid_t = 0);

template <typename... Ts>
CONCEALER_PUBLIC explicit FieldOperatorApplication(Ts &&... xs)
: FieldOperatorApplication(ros2_launch(std::forward<decltype(xs)>(xs)...))
{
}
CONCEALER_PUBLIC explicit FieldOperatorApplication(const pid_t);

~FieldOperatorApplication();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,6 @@ class EgoEntity : public VehicleEntity
{
const std::unique_ptr<concealer::FieldOperatorApplication> field_operator_application;

static auto makeFieldOperatorApplication(
const Configuration &, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &)
-> std::unique_ptr<concealer::FieldOperatorApplication>;

bool is_controlled_by_simulator_{false};
std::optional<double> target_speed_;
traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter_;
Expand Down
18 changes: 9 additions & 9 deletions simulation/traffic_simulator/src/entity/ego_entity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <boost/lexical_cast.hpp>
#include <concealer/field_operator_application.hpp>
#include <concealer/launch.hpp>
#include <functional>
#include <memory>
#include <optional>
Expand All @@ -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<concealer::FieldOperatorApplication>
Expand All @@ -56,11 +57,12 @@ auto EgoEntity::makeFieldOperatorApplication(
parameters.push_back("localization_sim_mode:=" + std::string(getParameter<bool>(node_parameters, "simulate_localization") ? "api" : "pose_twist_estimator"));
// clang-format on

return getParameter<bool>(node_parameters, "launch_autoware", true)
? std::make_unique<concealer::FieldOperatorApplication>(
getParameter<std::string>(node_parameters, "autoware_launch_package"),
getParameter<std::string>(node_parameters, "autoware_launch_file"), parameters)
: std::make_unique<concealer::FieldOperatorApplication>();
return std::make_unique<concealer::FieldOperatorApplication>(
getParameter<bool>(node_parameters, "launch_autoware", true)
? concealer::ros2_launch(
getParameter<std::string>(node_parameters, "autoware_launch_package"),
getParameter<std::string>(node_parameters, "autoware_launch_file"), parameters)
: 0);
} else {
throw common::SemanticError(
"Unexpected architecture_type ", std::quoted(architecture_type), " was given.");
Expand Down Expand Up @@ -113,9 +115,7 @@ auto EgoEntity::getRouteLanelets(double /*unused horizon*/) -> lanelet::Ids
{
lanelet::Ids ids{};

if (const auto universe =
dynamic_cast<concealer::FieldOperatorApplication *>(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;
}
Expand Down

0 comments on commit 544fd7b

Please sign in to comment.