diff --git a/awapi/awapi_awiv_adapter/CMakeLists.txt b/awapi/awapi_awiv_adapter/CMakeLists.txt
deleted file mode 100644
index 2f6171b969440..0000000000000
--- a/awapi/awapi_awiv_adapter/CMakeLists.txt
+++ /dev/null
@@ -1,35 +0,0 @@
-cmake_minimum_required(VERSION 3.5)
-project(awapi_awiv_adapter)
-
-if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
- set(CMAKE_CXX_STANDARD_REQUIRED ON)
- set(CMAKE_CXX_EXTENSIONS OFF)
-endif()
-if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
- add_compile_options(-Wall -Wextra -Wpedantic -Werror)
-endif()
-
-find_package(ament_cmake_auto REQUIRED)
-ament_auto_find_build_dependencies()
-
-ament_auto_add_executable(awapi_awiv_adapter
- src/awapi_awiv_adapter_node.cpp
- src/awapi_awiv_adapter_core.cpp
- src/awapi_vehicle_state_publisher.cpp
- src/awapi_autoware_state_publisher.cpp
- src/awapi_stop_reason_aggregator.cpp
- src/awapi_v2x_aggregator.cpp
- src/awapi_lane_change_state_publisher.cpp
- src/awapi_obstacle_avoidance_state_publisher.cpp
- src/awapi_max_velocity_publisher.cpp
- src/awapi_autoware_util.cpp
- src/awapi_pacmod_util.cpp
-)
-
-if(BUILD_TESTING)
- find_package(ament_lint_auto REQUIRED)
- ament_lint_auto_find_test_dependencies()
-endif()
-
-ament_auto_package(INSTALL_TO_SHARE launch)
diff --git a/awapi/awapi_awiv_adapter/Readme.md b/awapi/awapi_awiv_adapter/Readme.md
deleted file mode 100644
index b762812173e22..0000000000000
--- a/awapi/awapi_awiv_adapter/Readme.md
+++ /dev/null
@@ -1,299 +0,0 @@
-# awapi_awiv_adapter
-
-✓: confirmed, (blank): not confirmed
-
-## get topic
-
-### /awapi/vehicle/get/status
-
-- get vehicle status
-- MessageType: awapi_awiv_adapter/AwapiVehicleStatus
-
-| ✓ | type | name | unit | note |
-| --- | :----------------------- | :----------------------- | :----------------------------------------- | :--------------------------------------- |
-| ✓ | std_msgs/Header | header | | |
-| ✓ | geometry_msgs/Pose | pose | position:[m] | |
-| ✓ | awapi_awiv_adapter/Euler | eulerangle | [rad] | roll/pitch/yaw |
-| | geographic_msgs/GeoPoint | geo_point | | lat/lon/alt |
-| ✓ | float64 | velocity | [m/s] | |
-| ✓ | float64 | acceleration | [m/ss] | calculate from velocity in awapi_adapter |
-| ✓ | float64 | steering | [rad] | |
-| ✓ | float64 | steering_velocity | [rad/s] | calculate from steering in awapi_adapter |
-| ✓ | float64 | angular_velocity | [rad/s] | |
-| | int32 | gear | according to tier4_vehicle_msgs/Shift | |
-| | float32 | energy_level | | available only for golf-cart |
-| ✓ | int32 | turn_signal | according to tier4_vehicle_msgs/TurnSignal | |
-| ✓ | float64 | target_velocity | [m/s] | |
-| ✓ | float64 | target_acceleration | [m/ss] | |
-| ✓ | float64 | target_steering | [rad] | |
-| ✓ | float64 | target_steering_velocity | [rad/s] | |
-
-### /awapi/autoware/get/status
-
-- get autoware status
-- MessageType: awapi_awiv_adapter/AwapiVehicleStatus
-
-| ✓ | type | name | unit | note |
-| --- | :---------------------------------- | :------------------- | :------------------------------------------ | :-------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
-| ✓ | std_msgs/Header | header | | |
-| ✓ | string | autoware_state | | |
-| ✓ | int32 | control_mode | according to tier4_vehicle_msgs/ControlMode | manual/auto (changed by /awapi/autoware/put/engage) |
-| | int32 | gate_mode | tier4_vehicle_msgs/GateMode | auto/remote (it is valid only when control_mode=auto)) |
-| ✓ | bool | emergency_stopped | True in emergency mode | |
-| ✓ | float32 | current_max_velocity | [m/s] | |
-| | tier4_system_msgs/HazardStatus | hazard_status | | system hazard status |
-| ✓ | tier4_planning_msgs/StopReasonArray | stop_reason | | "stop_pose" represents the position of "base_link" (not the head of the car) |
-| ✓ | diagnostic_msgs/DiagnosticStatus[] | diagnostics | | output only diag. of leaf node (diag. of parent node are cut) |
-| ✓ | diagnostic_msgs/DiagnosticStatus[] | error_diagnostics | | diagnostics that are the cause of system emergency |
-| ✓ | bool | arrived_goal | | True if the autoware_state is changed from Driving to ArrivedGoal or WaitingForRoute. False if the autoware_state is changed to WaitingForEngage or Driving. Default False. |
-
-- specification of stop_reason
- - stop_reason is output only when the following conditions are met.
- - stop_point in stop_reason is close to /planning/scenario_planning/trajectory (within 10m).
- - The distance between current position and stop_point is less than stop_reason_thresh_dist.
-
-### /awapi/autoware/get/route
-
-- get route
-- MessageType: tier4_planning_msgs/Route
-
-| ✓ | type | name | unit | note |
-| --- | :------------------------ | :--- | :--- | :--- |
-| ✓ | tier4_planning_msgs/Route | | | |
-
-### /awapi/autoware/get/stop_speed_exceeded
-
-- get flag of exceeding stop speed or not
- - True: exceed the stop speed ( = "cannot stop before the stop line")
- - False: not exceed the stop speed ( = "no stop line in the trajectory" or "possible to stop before the stop line" )
-- MessageType: tier4_planning_msgs/StopSpeedExceedStatus
-
-| ✓ | type | name | unit | note |
-| --- | :---------------------------------------- | :--- | :--- | :--- |
-| | tier4_planning_msgs/StopSpeedExceedStatus | | - | |
-
-### /awapi/prediction/get/objects
-
-- get predicted object
-- MessageType: tier4_api_msgs/DynamicObjectArray
-
-| ✓ | type | name | unit | note |
-| --- | :-------------------------------- | :--- | :--- | :--- |
-| ✓ | tier4_api_msgs/DynamicObjectArray | | | |
-
-### /awapi/lane_change/get/status
-
-- get lane change information
-- MessageType: awapi_awiv_adapter/LaneChangeStatus
-
-| ✓ | type | name | unit | note |
-| --- | :----------------------- | :-------------------------- | :------------------------------------ | :--------------------------------------------------------------------------------- |
-| | std_msgs/Header | header | | |
-| | bool | force_lane_change_available | True when lane change is available | available: Physically lane changeable state (do not consider other vehicle) |
-| | bool | lane_change_ready | True when lane change is ready | ready: State that ego-vehicle can change lane without collision with other vehicle |
-| | tier4_planning_msgs/Path | candidate_path | according to tier4_planning_msgs/Path | |
-
-### /awapi/object_avoidance/get/status
-
-- get obstacle avoidance information
-- MessageType: awapi_awiv_adapter/ObstacleAvoidanceStatus
-
-| ✓ | type | name | unit | note |
-| --- | :----------------------------- | :----------------------- | :------------------------------------------ | :---------------------------------------------------- |
-| | std_msgs/Header | header | | |
-| | bool | obstacle_avoidance_ready | True when obstacle avoidance is ready | |
-| | tier4_planning_msgs/Trajectory | candidate_path | according to tier4_planning_msgs/Trajectory | Msg type is different from lane change candidate path |
-
-### /awapi/traffic_light/get/traffic_signals
-
-- get recognition result of traffic light
-- MessageType: autoware_auto_perception_msgs/msg/TrafficSignalArray
-
-| ✓ | type | name | unit | note |
-| --- | :--------------------------------------------------- | :--- | :--- | :--- |
-| | autoware_auto_perception_msgs/msg/TrafficSignalArray | | | |
-
-### /awapi/traffic_light/get/nearest_traffic_signal
-
-- get recognition result of nearest traffic light
-- MessageType: autoware_auto_perception_msgs/LookingTrafficSignal
-
-| | type | name | unit | note |
-| --- | :--------------------------------------------------- | :--------- | :--- | :------------------------------------------------------------ |
-| | std_msgs/Header | header | | |
-| | autoware_auto_perception_msgs/TrafficSignalWithJudge | perception | | traffic light information from autoware perception module |
-| | autoware_auto_perception_msgs/TrafficSignalWithJudge | external | | traffic light information from external tool/module |
-| | autoware_auto_perception_msgs/TrafficSignalWithJudge | final | | traffic light information used by the planning module finally |
-
-- The contents of TrafficSignalWithJudge.msg is following.
-
-| | type | name | unit | note |
-| --- | :------------------------------------------ | :----- | :------------------- | :------------------------------------------------------------- |
-| | autoware_auto_perception_msgs/TrafficSignal | signal | | traffic light color/arrow |
-| | uint8 | judge | 0:NONE, 1:STOP, 2:GO | go/stop judgment based on the color/arrow of the traffic light |
-
-### /awapi/vehicle/get/door
-
-- get door status
-- MessageType: tier4_api_msgs/DoorStatus.msg
-
-| ✓ | type | name | unit | note |
-| --- | :------------------------ | :----- | :--------------------------------------------------------------------------------------- | :------------------------------------------ |
-| | tier4_api_msgs/DoorStatus | status | 0:UNKNOWN, 1:DOOR_OPENED, 2:DOOR_CLOSED 3:DOOR_OPENING, 4:DOOR_CLOSING, 5:NOT_APPLICABLE | available only for the vehicle using pacmod |
-
-- Now, available status is following: (0:UNKNOWN, 1:DOOR_OPENED, 2:DOOR_CLOSED, 5:NOT_APPLICABLE ).
-- 5 (NOT_APPLICABLE) is published if the pacmod is not used
-- Due to the specifications of pacmod, the last door open / close command is published as the status.
-- The status is 0 (UNKNOWN) until the door open / close command is published once.
-
-## put topic
-
-### /awapi/vehicle/put/velocity
-
-- set upper velocity
-- MessageType: tier4_api_msgs/VelocityLimit
-
-| ✓ | type | name | unit | note |
-| --- | :--------------------------- | :--- | :--- | :----------- |
-| ✓ | tier4_api_msgs/VelocityLimit | | | max velocity |
-
-### /awapi/vehicle/put/stop
-
-- set temporary stop signal
-- MessageType: tier4_api_msgs/StopCommand
-- Specification
-
- - send True: send upper velocity to 0
- - send False: resend last received upper velocity
- - (if upper velocity have never received, send _default_max_velocity_ value.)
- - _default_max_velocity_ refers to the param: _/planning/scenario_planning/motion_velocity_optimizer/max_velocity_
-
- | ✓ | type | name | unit | note |
- | --- | :------------------------- | :--- | :--- | :--- |
- | ✓ | tier4_api_msgs/StopCommand | | | |
-
-### /awapi/autoware/put/gate_mode
-
-- send gate mode (auto/remote)
-- MessageType: tier4_control_msgs/GateMode
-
-| ✓ | type | name | unit | note |
-| --- | :-------------------------- | :--- | :--- | :--- |
-| | tier4_control_msgs/GateMode | | | |
-
-### /awapi/autoware/put/engage
-
-- send engage signal (both of autoware/engage and vehicle/engage)
-- MessageType: tier4_vehicle_msgs/Engage
-
-| ✓ | type | name | unit | note |
-| --- | :------------------------ | :--- | :--- | :--- |
-| ✓ | tier4_vehicle_msgs/Engage | | | |
-
-### /awapi/autoware/put/goal
-
-- send goal pose
-- MessageType: geometry_msgs/PoseStamped
-
-| ✓ | type | name | unit | note |
-| --- | :------------------------ | :--- | :--- | :--- |
-| | geometry_msgs/PoseStamped | | | |
-
-### /awapi/autoware/put/route
-
-- send route
-- MessageType: tier4_planning_msgs/Route
-
-| ✓ | type | name | unit | note |
-| --- | :------------------------ | :--- | :--- | :--- |
-| ✓ | tier4_planning_msgs/Route | | | |
-
-### /awapi/lane_change/put/approval
-
-- send lane change approval flag
-- send True: start lane change when **lane_change_ready** is true
-- MessageType: tier4_planning_msgs/LaneChangeCommand
-
-| ✓ | type | name | unit | note |
-| --- | :---------------------------------------- | :--- | :--- | :--- |
-| | tier4_planning_msgs/msg/LaneChangeCommand | | | |
-
-### /awapi/lane_change/put/force
-
-- send force lane change flag
-- send True: start lane change when **force_lane_change_available** is true
-- MessageType: tier4_planning_msgs/LaneChangeCommand
-
-| ✓ | type | name | unit | note |
-| --- | :------------------------------------ | :--- | :--- | :--- |
-| | tier4_planning_msgs/LaneChangeCommand | | | |
-
-### /awapi/object_avoidance/put/approval
-
-- send object avoidance approval flag
-- MessageType: tier4_planning_msgs/EnableAvoidance
-
-| ✓ | type | name | unit | note |
-| --- | :---------------------------------- | :--- | :--- | :--- |
-| | tier4_planning_msgs/EnableAvoidance | | | |
-
-### /awapi/object_avoidance/put/force
-
-- send force object avoidance flag
-- **not implemented (Autoware does not have corresponded topic)**
-
-| ✓ | type | name | unit | note |
-| --- | :--- | :--- | :--- | :--- |
-
-### /awapi/traffic_light/put/traffic_signals
-
-- Overwrite the recognition result of traffic light
-- MessageType: autoware_auto_perception_msgs/TrafficSignalArray
-
-| ✓ | type | name | unit | note |
-| --- | :----------------------------------------------- | :--- | :--- | :--- |
-| | autoware_auto_perception_msgs/TrafficSignalArray | | | |
-
-### /awapi/vehicle/put/door
-
-- send door command
-- MessageType: tier4_api_msgs/DoorCommand
- - send True: open door
- - send False: close door
-
-| ✓ | type | name | unit | note |
-| --- | :------------------------- | :--- | :--- | :------------------------------------------ |
-| | tier4_api_msgs/DoorCommand | | | available only for the vehicle using pacmod |
-
-### /awapi/autoware/put/crosswalk_states
-
-- send crosswalk status
- - forcibly rewrite the internal state of crosswalk module
-- MessageType: tier4_api_msgs/CrossWalkStatus
-
-| ✓ | type | name | unit | note |
-| --- | :-------------- | :----- | :----------------------- | :--- |
-| | std_msgs/Header | header | | |
-| | int32 | status | 0:STOP, 1:GO, 2:SLOWDOWN | |
-
-### /awapi/autoware/put/intersection_states
-
-- send intersection status
- - forcibly rewrite the internal state of intersection module
-- MessageType: tier4_api_msgs/CrosswalkStatus
-
-| ✓ | type | name | unit | note |
-| --- | :-------------- | :----- | :----------- | :--- |
-| | std_msgs/Header | header | | |
-| | int32 | status | 0:STOP, 1:GO | |
-
-### /awapi/autoware/put/expand_stop_range
-
-- send expand range of the polygon used by obstacle stop [m]
-- MessageType: tier4_planning_msgs/ExpandStopRange
-
-| ✓ | type | name | unit | note |
-| --- | :---------------------------------- | :--- | :--- | :--- |
-| | tier4_planning_msgs/ExpandStopRange | | | |
-
----
diff --git a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_state_publisher.hpp b/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_state_publisher.hpp
deleted file mode 100644
index 7352e43433276..0000000000000
--- a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_state_publisher.hpp
+++ /dev/null
@@ -1,80 +0,0 @@
-// Copyright 2020 Tier IV, Inc.
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef AWAPI_AWIV_ADAPTER__AWAPI_AUTOWARE_STATE_PUBLISHER_HPP_
-#define AWAPI_AWIV_ADAPTER__AWAPI_AUTOWARE_STATE_PUBLISHER_HPP_
-
-#include "awapi_awiv_adapter/awapi_autoware_util.hpp"
-
-#include
-
-#include
-
-#include
-#include
-#include
-
-namespace autoware_api
-{
-class AutowareIvAutowareStatePublisher
-{
-public:
- explicit AutowareIvAutowareStatePublisher(rclcpp::Node & node);
- void statePublisher(const AutowareInfo & aw_info);
-
-private:
- rclcpp::Logger logger_;
- rclcpp::Clock::SharedPtr clock_;
- // publisher
- rclcpp::Publisher::SharedPtr pub_state_;
-
- // parameter
-
- /* parameter for judging goal now */
- bool arrived_goal_;
- autoware_auto_system_msgs::msg::AutowareState::_state_type prev_state_;
-
- void getAutowareStateInfo(
- const autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr & autoware_state_ptr,
- tier4_api_msgs::msg::AwapiAutowareStatus * status);
- void getControlModeInfo(
- const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr & control_mode_ptr,
- tier4_api_msgs::msg::AwapiAutowareStatus * status);
- void getGateModeInfo(
- const tier4_control_msgs::msg::GateMode::ConstSharedPtr & gate_mode_ptr,
- tier4_api_msgs::msg::AwapiAutowareStatus * status);
- void getEmergencyStateInfo(
- const autoware_auto_system_msgs::msg::EmergencyState::ConstSharedPtr & emergency_state_ptr,
- tier4_api_msgs::msg::AwapiAutowareStatus * status);
- void getCurrentMaxVelInfo(
- const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr & current_max_velocity_ptr,
- tier4_api_msgs::msg::AwapiAutowareStatus * status);
- void getHazardStatusInfo(
- const AutowareInfo & aw_info, tier4_api_msgs::msg::AwapiAutowareStatus * status);
- void getStopReasonInfo(
- const tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr & stop_reason_ptr,
- tier4_api_msgs::msg::AwapiAutowareStatus * status);
- void getDiagInfo(const AutowareInfo & aw_info, tier4_api_msgs::msg::AwapiAutowareStatus * status);
- void getErrorDiagInfo(
- const AutowareInfo & aw_info, tier4_api_msgs::msg::AwapiAutowareStatus * status);
- void getGlobalRptInfo(
- const pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr & global_rpt_ptr,
- tier4_api_msgs::msg::AwapiAutowareStatus * status);
-
- bool isGoal(const autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr & autoware_state);
-};
-
-} // namespace autoware_api
-
-#endif // AWAPI_AWIV_ADAPTER__AWAPI_AUTOWARE_STATE_PUBLISHER_HPP_
diff --git a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_util.hpp b/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_util.hpp
deleted file mode 100644
index bacca29abfa15..0000000000000
--- a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_util.hpp
+++ /dev/null
@@ -1,148 +0,0 @@
-// Copyright 2020 Tier IV, Inc.
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef AWAPI_AWIV_ADAPTER__AWAPI_AUTOWARE_UTIL_HPP_
-#define AWAPI_AWIV_ADAPTER__AWAPI_AUTOWARE_UTIL_HPP_
-
-#include
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-#include
-
-#include
-#include
-
-namespace autoware_api
-{
-struct AutowareInfo
-{
- std::shared_ptr current_pose_ptr;
- autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr steer_ptr;
- autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr vehicle_cmd_ptr;
- autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr turn_indicators_ptr;
- autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr hazard_lights_ptr;
- nav_msgs::msg::Odometry::ConstSharedPtr odometry_ptr;
- autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr gear_ptr;
- tier4_vehicle_msgs::msg::BatteryStatus::ConstSharedPtr battery_ptr;
- sensor_msgs::msg::NavSatFix::ConstSharedPtr nav_sat_ptr;
- autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr autoware_state_ptr;
- autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_ptr;
- tier4_control_msgs::msg::GateMode::ConstSharedPtr gate_mode_ptr;
- autoware_auto_system_msgs::msg::EmergencyState::ConstSharedPtr emergency_state_ptr;
- autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr hazard_status_ptr;
- tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr stop_reason_ptr;
- tier4_v2x_msgs::msg::InfrastructureCommandArray::ConstSharedPtr v2x_command_ptr;
- tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr v2x_state_ptr;
- diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr diagnostic_ptr;
- pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr global_rpt_ptr;
- tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr lane_change_available_ptr;
- tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr lane_change_ready_ptr;
- autoware_auto_planning_msgs::msg::Path::ConstSharedPtr lane_change_candidate_ptr;
- tier4_planning_msgs::msg::IsAvoidancePossible::ConstSharedPtr obstacle_avoid_ready_ptr;
- autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr obstacle_avoid_candidate_ptr;
- tier4_api_msgs::msg::VelocityLimit::ConstSharedPtr max_velocity_ptr;
- tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr current_max_velocity_ptr;
- tier4_api_msgs::msg::StopCommand::ConstSharedPtr temporary_stop_ptr;
- autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr autoware_planning_traj_ptr;
- pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr door_state_ptr;
-};
-
-template
-T waitForParam(
- rclcpp::Node * node, const std::string & remote_node_name, const std::string & param_name)
-{
- std::chrono::seconds sec(1);
-
- auto param_client = std::make_shared(node, remote_node_name);
-
- while (!param_client->wait_for_service(sec)) {
- if (!rclcpp::ok()) {
- RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service.");
- return {};
- }
- RCLCPP_INFO_THROTTLE(
- node->get_logger(), *node->get_clock(), 1000 /* ms */, "waiting for node: %s, param: %s\n",
- remote_node_name.c_str(), param_name.c_str());
- }
-
- if (param_client->has_parameter(param_name)) {
- return param_client->get_parameter(param_name);
- }
-
- return {};
-}
-
-double lowpass_filter(const double current_value, const double prev_value, const double gain);
-
-namespace planning_util
-{
-bool calcClosestIndex(
- const autoware_auto_planning_msgs::msg::Trajectory & traj, const geometry_msgs::msg::Pose & pose,
- size_t & output_closest_idx, const double dist_thr = 10.0, const double angle_thr = M_PI / 2.0);
-
-inline geometry_msgs::msg::Pose getPose(
- const autoware_auto_planning_msgs::msg::Trajectory & traj, const int idx)
-{
- return traj.points.at(idx).pose;
-}
-
-inline double calcDist2d(const geometry_msgs::msg::Point & a, const geometry_msgs::msg::Point & b)
-{
- return std::hypot((a.x - b.x), (a.y - b.y));
-}
-
-double normalizeEulerAngle(double euler);
-
-double calcArcLengthFromWayPoint(
- const autoware_auto_planning_msgs::msg::Trajectory & input_path, const size_t src_idx,
- const size_t dst_idx);
-
-double calcDistanceAlongTrajectory(
- const autoware_auto_planning_msgs::msg::Trajectory & trajectory,
- const geometry_msgs::msg::Pose & current_pose, const geometry_msgs::msg::Pose & target_pose);
-
-} // namespace planning_util
-
-} // namespace autoware_api
-
-#endif // AWAPI_AWIV_ADAPTER__AWAPI_AUTOWARE_UTIL_HPP_
diff --git a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_awiv_adapter_core.hpp b/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_awiv_adapter_core.hpp
deleted file mode 100644
index 61d92f635e33e..0000000000000
--- a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_awiv_adapter_core.hpp
+++ /dev/null
@@ -1,188 +0,0 @@
-// Copyright 2020 Tier IV, Inc.
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef AWAPI_AWIV_ADAPTER__AWAPI_AWIV_ADAPTER_CORE_HPP_
-#define AWAPI_AWIV_ADAPTER__AWAPI_AWIV_ADAPTER_CORE_HPP_
-
-#include "awapi_awiv_adapter/awapi_autoware_state_publisher.hpp"
-#include "awapi_awiv_adapter/awapi_autoware_util.hpp"
-#include "awapi_awiv_adapter/awapi_lane_change_state_publisher.hpp"
-#include "awapi_awiv_adapter/awapi_max_velocity_publisher.hpp"
-#include "awapi_awiv_adapter/awapi_obstacle_avoidance_state_publisher.hpp"
-#include "awapi_awiv_adapter/awapi_pacmod_util.hpp"
-#include "awapi_awiv_adapter/awapi_stop_reason_aggregator.hpp"
-#include "awapi_awiv_adapter/awapi_v2x_aggregator.hpp"
-#include "awapi_awiv_adapter/awapi_vehicle_state_publisher.hpp"
-
-#include
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-
-namespace autoware_api
-{
-class AutowareIvAdapter : public rclcpp::Node
-{
-public:
- AutowareIvAdapter();
-
-private:
- // subscriber
- rclcpp::Subscription::SharedPtr sub_steer_;
- rclcpp::Subscription::SharedPtr
- sub_vehicle_cmd_;
- rclcpp::Subscription::SharedPtr
- sub_turn_indicators_;
- rclcpp::Subscription::SharedPtr
- sub_hazard_lights_;
- rclcpp::Subscription::SharedPtr sub_odometry_;
- rclcpp::Subscription::SharedPtr sub_gear_;
- rclcpp::Subscription::SharedPtr sub_battery_;
- rclcpp::Subscription::SharedPtr sub_nav_sat_;
- rclcpp::Subscription::SharedPtr
- sub_autoware_state_;
- rclcpp::Subscription::SharedPtr
- sub_control_mode_;
- rclcpp::Subscription::SharedPtr sub_gate_mode_;
- rclcpp::Subscription::SharedPtr sub_emergency_;
- rclcpp::Subscription::SharedPtr
- sub_hazard_status_;
- rclcpp::Subscription::SharedPtr sub_stop_reason_;
- rclcpp::Subscription::SharedPtr sub_v2x_command_;
- rclcpp::Subscription::SharedPtr
- sub_v2x_state_;
- rclcpp::Subscription::SharedPtr sub_diagnostics_;
- rclcpp::Subscription::SharedPtr sub_global_rpt_;
- rclcpp::Subscription::SharedPtr
- sub_lane_change_available_;
- rclcpp::Subscription::SharedPtr
- sub_lane_change_ready_;
- rclcpp::Subscription::SharedPtr
- sub_lane_change_candidate_;
- rclcpp::Subscription::SharedPtr
- sub_obstacle_avoid_ready_;
- rclcpp::Subscription::SharedPtr
- sub_obstacle_avoid_candidate_;
- rclcpp::Subscription::SharedPtr sub_max_velocity_;
- rclcpp::Subscription::SharedPtr
- sub_current_max_velocity_;
- rclcpp::Subscription::SharedPtr sub_temporary_stop_;
- rclcpp::Subscription::SharedPtr sub_autoware_traj_;
- rclcpp::Subscription::SharedPtr sub_door_control_;
- rclcpp::Subscription::SharedPtr sub_door_status_;
-
- // publisher
- rclcpp::Publisher::SharedPtr pub_door_control_;
- rclcpp::Publisher::SharedPtr pub_door_status_;
- rclcpp::Publisher::SharedPtr pub_v2x_command_;
- rclcpp::Publisher::SharedPtr pub_v2x_state_;
-
- // timer
- rclcpp::TimerBase::SharedPtr timer_;
-
- // tf
- tf2_ros::Buffer tf_buffer_;
- tf2_ros::TransformListener tf_listener_;
-
- // callback function
- void callbackSteer(const autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr msg_ptr);
- void callbackVehicleCmd(
- const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg_ptr);
- void callbackTurnIndicators(
- const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr msg_ptr);
- void callbackHazardLights(
- const autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr msg_ptr);
- void callbackTwist(const nav_msgs::msg::Odometry::ConstSharedPtr msg_ptr);
- void callbackGear(const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg_ptr);
- void callbackBattery(const tier4_vehicle_msgs::msg::BatteryStatus::ConstSharedPtr msg_ptr);
- void callbackNavSat(const sensor_msgs::msg::NavSatFix::ConstSharedPtr msg_ptr);
- void callbackAutowareState(
- const autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr msg_ptr);
- void callbackControlMode(
- const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg_ptr);
- void callbackGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg_ptr);
- void callbackEmergencyState(
- const autoware_auto_system_msgs::msg::EmergencyState::ConstSharedPtr msg_ptr);
- void callbackHazardStatus(
- const autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg_ptr);
- void callbackStopReason(const tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr msg_ptr);
- void callbackV2XCommand(
- const tier4_v2x_msgs::msg::InfrastructureCommandArray::ConstSharedPtr msg_ptr);
- void callbackV2XState(
- const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg_ptr);
- void callbackDiagnostics(const diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg_ptr);
- void callbackGlobalRpt(const pacmod3_msgs::msg::GlobalRpt::ConstSharedPtr msg_ptr);
- void callbackLaneChangeAvailable(
- const tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr msg_ptr);
- void callbackLaneChangeReady(
- const tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr msg_ptr);
- void callbackLaneChangeCandidatePath(
- const autoware_auto_planning_msgs::msg::Path::ConstSharedPtr msg_ptr);
- void callbackLaneObstacleAvoidReady(
- const tier4_planning_msgs::msg::IsAvoidancePossible::ConstSharedPtr msg_ptr);
- void callbackLaneObstacleAvoidCandidatePath(
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr);
- void callbackMaxVelocity(const tier4_api_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr);
- void callbackCurrentMaxVelocity(
- const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr);
- void callbackTemporaryStop(const tier4_api_msgs::msg::StopCommand::ConstSharedPtr msg_ptr);
- void callbackAutowareTrajectory(
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr);
- void callbackDoorControl(const tier4_api_msgs::msg::DoorControlCommand::ConstSharedPtr msg_ptr);
- void callbackDoorStatus(const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr msg_ptr);
-
- // timer function
- void timerCallback();
-
- void emergencyParamCheck(const bool emergency_stop_param);
- void getCurrentPose();
-
- // parameter
- AutowareInfo aw_info_;
- std::unique_ptr vehicle_state_publisher_;
- std::unique_ptr autoware_state_publisher_;
- std::unique_ptr stop_reason_aggregator_;
- std::unique_ptr v2x_aggregator_;
- std::unique_ptr lane_change_state_publisher_;
- std::unique_ptr obstacle_avoidance_state_publisher_;
- std::unique_ptr max_velocity_publisher_;
- double status_pub_hz_;
- double stop_reason_timeout_;
- double stop_reason_thresh_dist_;
-};
-
-} // namespace autoware_api
-
-#endif // AWAPI_AWIV_ADAPTER__AWAPI_AWIV_ADAPTER_CORE_HPP_
diff --git a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_lane_change_state_publisher.hpp b/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_lane_change_state_publisher.hpp
deleted file mode 100644
index c540aa7992ae8..0000000000000
--- a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_lane_change_state_publisher.hpp
+++ /dev/null
@@ -1,52 +0,0 @@
-// Copyright 2020 Tier IV, Inc.
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef AWAPI_AWIV_ADAPTER__AWAPI_LANE_CHANGE_STATE_PUBLISHER_HPP_
-#define AWAPI_AWIV_ADAPTER__AWAPI_LANE_CHANGE_STATE_PUBLISHER_HPP_
-
-#include "awapi_awiv_adapter/awapi_autoware_util.hpp"
-
-#include
-
-#include
-
-namespace autoware_api
-{
-class AutowareIvLaneChangeStatePublisher
-{
-public:
- explicit AutowareIvLaneChangeStatePublisher(rclcpp::Node & node);
- void statePublisher(const AutowareInfo & aw_info);
-
-private:
- rclcpp::Logger logger_;
- rclcpp::Clock::SharedPtr clock_;
-
- // publisher
- rclcpp::Publisher::SharedPtr pub_state_;
-
- void getLaneChangeAvailableInfo(
- const tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr & available_ptr,
- tier4_api_msgs::msg::LaneChangeStatus * status);
- void getLaneChangeReadyInfo(
- const tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr & ready_ptr,
- tier4_api_msgs::msg::LaneChangeStatus * status);
- void getCandidatePathInfo(
- const autoware_auto_planning_msgs::msg::Path::ConstSharedPtr & path_ptr,
- tier4_api_msgs::msg::LaneChangeStatus * status);
-};
-
-} // namespace autoware_api
-
-#endif // AWAPI_AWIV_ADAPTER__AWAPI_LANE_CHANGE_STATE_PUBLISHER_HPP_
diff --git a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_max_velocity_publisher.hpp b/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_max_velocity_publisher.hpp
deleted file mode 100644
index 507afd688af9e..0000000000000
--- a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_max_velocity_publisher.hpp
+++ /dev/null
@@ -1,46 +0,0 @@
-// Copyright 2020 Tier IV, Inc.
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef AWAPI_AWIV_ADAPTER__AWAPI_MAX_VELOCITY_PUBLISHER_HPP_
-#define AWAPI_AWIV_ADAPTER__AWAPI_MAX_VELOCITY_PUBLISHER_HPP_
-
-#include "awapi_awiv_adapter/awapi_autoware_util.hpp"
-
-#include
-
-#include
-
-namespace autoware_api
-{
-class AutowareIvMaxVelocityPublisher
-{
-public:
- AutowareIvMaxVelocityPublisher(rclcpp::Node & node, const double default_max_velocity);
- void statePublisher(const AutowareInfo & aw_info);
-
-private:
- // publisher
- rclcpp::Publisher::SharedPtr pub_state_;
-
- bool calcMaxVelocity(
- const tier4_api_msgs::msg::VelocityLimit::ConstSharedPtr & max_velocity_ptr,
- const tier4_api_msgs::msg::StopCommand::ConstSharedPtr & temporary_stop_ptr,
- float * max_velocity);
-
- double default_max_velocity_;
-};
-
-} // namespace autoware_api
-
-#endif // AWAPI_AWIV_ADAPTER__AWAPI_MAX_VELOCITY_PUBLISHER_HPP_
diff --git a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_obstacle_avoidance_state_publisher.hpp b/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_obstacle_avoidance_state_publisher.hpp
deleted file mode 100644
index 7ac755e8102c6..0000000000000
--- a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_obstacle_avoidance_state_publisher.hpp
+++ /dev/null
@@ -1,49 +0,0 @@
-// Copyright 2020 Tier IV, Inc.
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef AWAPI_AWIV_ADAPTER__AWAPI_OBSTACLE_AVOIDANCE_STATE_PUBLISHER_HPP_
-#define AWAPI_AWIV_ADAPTER__AWAPI_OBSTACLE_AVOIDANCE_STATE_PUBLISHER_HPP_
-
-#include "awapi_awiv_adapter/awapi_autoware_util.hpp"
-
-#include
-
-#include
-
-namespace autoware_api
-{
-class AutowareIvObstacleAvoidanceStatePublisher
-{
-public:
- explicit AutowareIvObstacleAvoidanceStatePublisher(rclcpp::Node & node);
- void statePublisher(const AutowareInfo & aw_info);
-
-private:
- rclcpp::Logger logger_;
- rclcpp::Clock::SharedPtr clock_;
-
- // publisher
- rclcpp::Publisher::SharedPtr pub_state_;
-
- void getObstacleAvoidReadyInfo(
- const tier4_planning_msgs::msg::IsAvoidancePossible::ConstSharedPtr & ready_ptr,
- tier4_api_msgs::msg::ObstacleAvoidanceStatus * status);
- void getCandidatePathInfo(
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr & path_ptr,
- tier4_api_msgs::msg::ObstacleAvoidanceStatus * status);
-};
-
-} // namespace autoware_api
-
-#endif // AWAPI_AWIV_ADAPTER__AWAPI_OBSTACLE_AVOIDANCE_STATE_PUBLISHER_HPP_
diff --git a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_pacmod_util.hpp b/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_pacmod_util.hpp
deleted file mode 100644
index 8426a385e3a65..0000000000000
--- a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_pacmod_util.hpp
+++ /dev/null
@@ -1,40 +0,0 @@
-// Copyright 2020 Tier IV, Inc.
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef AWAPI_AWIV_ADAPTER__AWAPI_PACMOD_UTIL_HPP_
-#define AWAPI_AWIV_ADAPTER__AWAPI_PACMOD_UTIL_HPP_
-
-#include
-
-#include
-#include
-#include
-#include
-
-namespace autoware_api
-{
-namespace pacmod_util
-{
-tier4_api_msgs::msg::DoorStatus getDoorStatusMsg(
- const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr & msg_ptr);
-pacmod3_msgs::msg::SystemCmdInt createClearOverrideDoorCommand(
- const rclcpp::Clock::SharedPtr & clock);
-pacmod3_msgs::msg::SystemCmdInt createDoorCommand(
- const rclcpp::Clock::SharedPtr & clock,
- const tier4_api_msgs::msg::DoorControlCommand::ConstSharedPtr & msg_ptr);
-} // namespace pacmod_util
-
-} // namespace autoware_api
-
-#endif // AWAPI_AWIV_ADAPTER__AWAPI_PACMOD_UTIL_HPP_
diff --git a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_stop_reason_aggregator.hpp b/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_stop_reason_aggregator.hpp
deleted file mode 100644
index b05ec18817537..0000000000000
--- a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_stop_reason_aggregator.hpp
+++ /dev/null
@@ -1,64 +0,0 @@
-// Copyright 2020 Tier IV, Inc.
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef AWAPI_AWIV_ADAPTER__AWAPI_STOP_REASON_AGGREGATOR_HPP_
-#define AWAPI_AWIV_ADAPTER__AWAPI_STOP_REASON_AGGREGATOR_HPP_
-
-#include "awapi_awiv_adapter/awapi_autoware_util.hpp"
-
-#include
-
-#include
-
-namespace autoware_api
-{
-class AutowareIvStopReasonAggregator
-{
-public:
- AutowareIvStopReasonAggregator(
- rclcpp::Node & node, const double timeout, const double thresh_dist_to_stop_pose);
- tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr updateStopReasonArray(
- const tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr & msg_ptr,
- const AutowareInfo & aw_info);
-
-private:
- void applyUpdate(
- const tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr & msg_ptr,
- const AutowareInfo & aw_info);
- bool checkMatchingReason(
- const tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr & msg_stop_reason_array,
- const tier4_planning_msgs::msg::StopReasonArray & stop_reason_array);
- void applyTimeOut();
- void appendStopReasonToArray(
- const tier4_planning_msgs::msg::StopReason & stop_reason,
- tier4_planning_msgs::msg::StopReasonArray * stop_reason_array, const AutowareInfo & aw_info);
- tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr makeStopReasonArray(
- const AutowareInfo & aw_info);
- tier4_planning_msgs::msg::StopReason inputStopDistToStopReason(
- const tier4_planning_msgs::msg::StopReason & stop_reason, const AutowareInfo & aw_info);
- double calcStopDistToStopFactor(
- const tier4_planning_msgs::msg::StopFactor & stop_factor, const AutowareInfo & aw_info);
- tier4_planning_msgs::msg::StopReason getNearStopReason(
- const tier4_planning_msgs::msg::StopReason & stop_reason, const AutowareInfo & aw_info);
-
- rclcpp::Logger logger_;
- rclcpp::Clock::SharedPtr clock_;
- double timeout_;
- double thresh_dist_to_stop_pose_;
- std::vector stop_reason_array_vec_;
-};
-
-} // namespace autoware_api
-
-#endif // AWAPI_AWIV_ADAPTER__AWAPI_STOP_REASON_AGGREGATOR_HPP_
diff --git a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_v2x_aggregator.hpp b/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_v2x_aggregator.hpp
deleted file mode 100644
index 11406da27deab..0000000000000
--- a/awapi/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_v2x_aggregator.hpp
+++ /dev/null
@@ -1,54 +0,0 @@
-// Copyright 2021 Tier IV, Inc.
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef AWAPI_AWIV_ADAPTER__AWAPI_V2X_AGGREGATOR_HPP_
-#define AWAPI_AWIV_ADAPTER__AWAPI_V2X_AGGREGATOR_HPP_
-
-#include
-
-#include
-#include
-
-#include