diff --git a/external/concealer/include/concealer/field_operator_application.hpp b/external/concealer/include/concealer/field_operator_application.hpp index ade08bd64d0..7118d87fdf7 100644 --- a/external/concealer/include/concealer/field_operator_application.hpp +++ b/external/concealer/include/concealer/field_operator_application.hpp @@ -54,19 +54,6 @@ namespace concealer { -/* ---- NOTE ------------------------------------------------------------------- - * - * The magic class 'FieldOperatorApplication' is a class that makes it easy to work with - * Autoware from C++. The main features of this class are as follows - * - * (1) Launch Autoware in an independent process upon instantiation of the - * class. - * (2) Properly terminates the Autoware process started by the constructor - * upon destruction of the class. - * (3) Probably the simplest instructions to Autoware, consisting of - * initialize, plan, and engage. - * - * -------------------------------------------------------------------------- */ struct FieldOperatorApplication : public rclcpp::Node, public TransitionAssertion { @@ -76,7 +63,7 @@ struct FieldOperatorApplication : public rclcpp::Node, const pid_t process_id = 0; - bool initialize_was_called = false; + bool initialized = false; std::string autoware_state = "LAUNCHING"; @@ -151,16 +138,8 @@ struct FieldOperatorApplication : public rclcpp::Node, auto clearRoute() -> void; - auto getMinimumRiskManeuverBehaviorName() const { return minimum_risk_maneuver_behavior; } - - auto getMinimumRiskManeuverStateName() const { return minimum_risk_maneuver_state; } - - auto getEmergencyStateName() const { return minimum_risk_maneuver_state; } - auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray; - auto initialized() const noexcept { return initialize_was_called; } - auto requestAutoModeForCooperation(const std::string &, bool) -> void; auto rethrow() const { task_queue.rethrow(); } diff --git a/external/concealer/src/field_operator_application.cpp b/external/concealer/src/field_operator_application.cpp index fc2d154dc33..3c037480171 100644 --- a/external/concealer/src/field_operator_application.cpp +++ b/external/concealer/src/field_operator_application.cpp @@ -348,7 +348,7 @@ auto FieldOperatorApplication::getWaypoints() const -> traffic_simulator_msgs::m auto FieldOperatorApplication::initialize(const geometry_msgs::msg::Pose & initial_pose) -> void { - if (not std::exchange(initialize_was_called, true)) { + if (not std::exchange(initialized, true)) { task_queue.delay([this, initial_pose]() { waitForAutowareStateToBe_WAITING_FOR_ROUTE([&]() { #if __has_include() diff --git a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp index b9cfae284bc..93e2a126cfb 100644 --- a/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp +++ b/openscenario/openscenario_interpreter/src/syntax/user_defined_value_condition.cpp @@ -131,18 +131,19 @@ UserDefinedValueCondition::UserDefinedValueCondition(const pugi::xml_node & node "currentMinimumRiskManeuverState.behavior", [result]() { return make( - asFieldOperatorApplication(result.str(1)).getMinimumRiskManeuverBehaviorName()); + asFieldOperatorApplication(result.str(1)).minimum_risk_maneuver_behavior); }), std::make_pair( "currentMinimumRiskManeuverState.state", [result]() { return make( - asFieldOperatorApplication(result.str(1)).getMinimumRiskManeuverStateName()); + asFieldOperatorApplication(result.str(1)).minimum_risk_maneuver_state); }), std::make_pair( "currentEmergencyState", [result]() { - return make(asFieldOperatorApplication(result.str(1)).getEmergencyStateName()); + return make( + asFieldOperatorApplication(result.str(1)).minimum_risk_maneuver_state); }), std::make_pair( "currentTurnIndicatorsState", diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index ca174980300..abb85f7885f 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -77,10 +77,7 @@ auto EgoEntity::asFieldOperatorApplication() -> concealer::FieldOperatorApplicat return *this; } -auto EgoEntity::getCurrentAction() const -> std::string -{ - return autoware_state; -} +auto EgoEntity::getCurrentAction() const -> std::string { return autoware_state; } auto EgoEntity::getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter { @@ -190,7 +187,7 @@ void EgoEntity::requestAssignRoute(const std::vector & route.push_back(pose_stamped); } - if (not initialized()) { + if (not initialized) { initialize(getMapPose()); plan(route); // NOTE: engage() will be executed at simulation-time 0.