Skip to content

Commit

Permalink
refactor: delete TasQueue
Browse files Browse the repository at this point in the history
  • Loading branch information
HansRobo committed Sep 10, 2024
1 parent 86513b2 commit 7dbfe81
Show file tree
Hide file tree
Showing 8 changed files with 1 addition and 143 deletions.
3 changes: 1 addition & 2 deletions external/concealer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
src/execute.cpp
src/field_operator_application.cpp
src/field_operator_application_for_autoware_universe.cpp
src/is_package_exists.cpp
src/task_queue.cpp)
src/is_package_exists.cpp)

target_link_libraries(${PROJECT_NAME}
atomic)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
#include <chrono>
#include <concealer/autoware_stream.hpp>
#include <concealer/launch.hpp>
#include <concealer/task_queue.hpp>
#include <concealer/visibility.hpp>
#include <exception>
#include <geometry_msgs/msg/accel.hpp>
Expand Down Expand Up @@ -66,8 +65,6 @@ class FieldOperatorApplication : public rclcpp::Node
protected:
const pid_t process_id = 0;

TaskQueue task_queue;

bool initialize_was_called = false;

auto stopRequest() noexcept -> void;
Expand Down Expand Up @@ -148,8 +145,6 @@ class FieldOperatorApplication : public rclcpp::Node
virtual auto getTurnIndicatorsCommand() const
-> autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand;

virtual auto rethrow() const noexcept(false) -> void;

virtual auto sendCooperateCommand(const std::string &, const std::string &) -> void = 0;

virtual auto setVelocityLimit(double) -> void = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@
#include <concealer/publisher_wrapper.hpp>
#include <concealer/service_with_validation.hpp>
#include <concealer/subscriber_wrapper.hpp>
#include <concealer/task_queue.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <tier4_external_api_msgs/msg/emergency.hpp>
#include <tier4_external_api_msgs/srv/engage.hpp>
Expand Down
66 changes: 0 additions & 66 deletions external/concealer/include/concealer/task_queue.hpp

This file was deleted.

2 changes: 0 additions & 2 deletions external/concealer/src/field_operator_application.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,8 +158,6 @@ auto FieldOperatorApplication::getTurnIndicatorsCommand() const
turn_indicators_command.stamp = now();
return turn_indicators_command;
}

auto FieldOperatorApplication::rethrow() const -> void { task_queue.rethrow(); }
} // namespace concealer

namespace autoware_auto_vehicle_msgs::msg
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ FieldOperatorApplicationFor<AutowareUniverse>::~FieldOperatorApplicationFor()
{
shutdownAutoware();
// All tasks should be complete before the services used in them will be deinitialized.
task_queue.stopAndJoin();
}

template <auto N, typename Tuples>
Expand Down Expand Up @@ -373,13 +372,11 @@ auto FieldOperatorApplicationFor<AutowareUniverse>::engage() -> void

auto FieldOperatorApplicationFor<AutowareUniverse>::engageable() const -> bool
{
rethrow();
return isWaitingForEngage();
}

auto FieldOperatorApplicationFor<AutowareUniverse>::engaged() const -> bool
{
rethrow();
return isDriving();
}

Expand Down
63 changes: 0 additions & 63 deletions external/concealer/src/task_queue.cpp

This file was deleted.

1 change: 0 additions & 1 deletion simulation/traffic_simulator/src/entity/ego_entity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,6 @@ auto EgoEntity::getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsAr

void EgoEntity::updateFieldOperatorApplication() const
{
field_operator_application->rethrow();
field_operator_application->spinSome();
}

Expand Down

0 comments on commit 7dbfe81

Please sign in to comment.