diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS
index 2fa3fa5812759..5af35b09f52bd 100644
--- a/.github/CODEOWNERS
+++ b/.github/CODEOWNERS
@@ -56,7 +56,7 @@ common/time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomo
common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp
common/traffic_light_utils/** kotaro.uetake@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp
common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp
-control/autonomous_emergency_braking/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp
+control/autonomous_emergency_braking/** daniel.sanchez@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp
control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
control/control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
control/external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
@@ -69,6 +69,7 @@ control/pid_longitudinal_controller/** mamoru.sobue@tier4.jp takamasa.horibe@tie
control/predicted_path_checker/** berkay@leodrive.ai
control/pure_pursuit/** takamasa.horibe@tier4.jp
control/shift_decider/** takamasa.horibe@tier4.jp
+control/smart_mpc_trajectory_follower/** masayuki.aino@proxima-ai-tech.com
control/trajectory_follower_base/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
control/trajectory_follower_node/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
control/vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp
@@ -155,6 +156,7 @@ perception/traffic_light_map_based_detector/** shunsuke.miura@tier4.jp tao.zhong
perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp
perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp
perception/traffic_light_visualization/** tao.zhong@tier4.jp yukihiro.saito@tier4.jp
+planning/autoware_planning_test_manager/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp
planning/autoware_remaining_distance_time_calculator/** ahmed.ebrahim@leodrive.ai
planning/autoware_static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp
planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp
@@ -183,7 +185,7 @@ planning/behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kur
planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
planning/behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp
planning/behavior_velocity_template_module/** daniel.sanchez@tier4.jp
-planning/behavior_velocity_traffic_light_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
+planning/behavior_velocity_traffic_light_module/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
planning/behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
planning/behavior_velocity_walkway_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
@@ -198,7 +200,7 @@ planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.j
planning/obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp
planning/path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp
-planning/planning_test_utils/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp
+planning/planning_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp
planning/planning_topic_converter/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp
planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp
planning/route_handler/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp zulfaqar.azmi@tier4.jp
@@ -225,7 +227,7 @@ sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp
simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp
simulator/fault_injection/** keisuke.shima@tier4.jp
simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tier4.jp
-simulator/simple_planning_simulator/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp
+simulator/simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp
simulator/vehicle_door_simulator/** isamu.takagi@tier4.jp
system/autoware_auto_msgs_adapter/** isamu.takagi@tier4.jp mfc@leodrive.ai
system/bluetooth_monitor/** fumihito.ito@tier4.jp
@@ -249,6 +251,7 @@ system/system_error_monitor/** fumihito.ito@tier4.jp
system/system_monitor/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp
system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp
system/velodyne_monitor/** fumihito.ito@tier4.jp
+tools/reaction_analyzer/** berkay@leodrive.ai
vehicle/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp
vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp
vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp
diff --git a/common/mission_planner_rviz_plugin/CMakeLists.txt b/common/mission_planner_rviz_plugin/CMakeLists.txt
deleted file mode 100644
index 2b06e6db3e70d..0000000000000
--- a/common/mission_planner_rviz_plugin/CMakeLists.txt
+++ /dev/null
@@ -1,23 +0,0 @@
-cmake_minimum_required(VERSION 3.14)
-project(mission_planner_rviz_plugin)
-
-find_package(autoware_cmake REQUIRED)
-autoware_package()
-
-find_package(Qt5 REQUIRED Core Widgets)
-set(QT_LIBRARIES Qt5::Widgets)
-set(CMAKE_AUTOMOC ON)
-set(CMAKE_INCLUDE_CURRENT_DIR ON)
-
-ament_auto_add_library(${PROJECT_NAME} SHARED
- src/mrm_goal.cpp
- src/route_selector_panel.cpp
-)
-
-target_link_libraries(${PROJECT_NAME}
- ${QT_LIBRARIES}
-)
-
-pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml)
-
-ament_auto_package()
diff --git a/common/mission_planner_rviz_plugin/README.md b/common/mission_planner_rviz_plugin/README.md
deleted file mode 100644
index 59d36a0a2f840..0000000000000
--- a/common/mission_planner_rviz_plugin/README.md
+++ /dev/null
@@ -1,18 +0,0 @@
-# mission_planner_rviz_plugin
-
-## MrmGoalTool
-
-This is a copy of `rviz_default_plugins::tools::GoalTool`. Used together with the RouteSelectorPanel to set the MRM route.
-After adding the tool, change the topic name to `/rviz/route_selector/mrm/goal` from the topic property panel in rviz.
-
-## RouteSelectorPanel
-
-This panel shows the main and mrm route state in the route_selector and the route states in the mission_planner.
-Additionally, it provides clear and set functions for each main route and mrm route.
-
-| Trigger | Action |
-| -------------------------------------- | ------------------------------------------------------------------------ |
-| main route clear button | call `/planning/mission_planning/route_selector/main/clear_route` |
-| mrm route clear button | call `/planning/mission_planning/route_selector/mrm/clear_route` |
-| `/rviz/route_selector/main/goal` topic | call `/planning/mission_planning/route_selector/main/set_waypoint_route` |
-| `/rviz/route_selector/mrm/goal` topic | call `/planning/mission_planning/route_selector/mrm/set_waypoint_route` |
diff --git a/common/mission_planner_rviz_plugin/package.xml b/common/mission_planner_rviz_plugin/package.xml
deleted file mode 100644
index e45cf2739f260..0000000000000
--- a/common/mission_planner_rviz_plugin/package.xml
+++ /dev/null
@@ -1,29 +0,0 @@
-
-
-
- mission_planner_rviz_plugin
- 0.0.0
- The mission_planner_rviz_plugin package
- Takagi, Isamu
- Apache License 2.0
-
- ament_cmake_auto
- autoware_cmake
-
- geometry_msgs
- libqt5-core
- libqt5-gui
- libqt5-widgets
- rclcpp
- rviz_common
- rviz_default_plugins
- tier4_planning_msgs
-
- ament_lint_auto
- autoware_lint_common
-
-
- ament_cmake
-
-
-
diff --git a/common/mission_planner_rviz_plugin/plugins/plugin_description.xml b/common/mission_planner_rviz_plugin/plugins/plugin_description.xml
deleted file mode 100644
index c8285fcc604d7..0000000000000
--- a/common/mission_planner_rviz_plugin/plugins/plugin_description.xml
+++ /dev/null
@@ -1,8 +0,0 @@
-
-
- MrmGoalTool
-
-
- RouteSelectorPanel
-
-
diff --git a/common/mission_planner_rviz_plugin/src/mrm_goal.cpp b/common/mission_planner_rviz_plugin/src/mrm_goal.cpp
deleted file mode 100644
index ef5529abfb4a7..0000000000000
--- a/common/mission_planner_rviz_plugin/src/mrm_goal.cpp
+++ /dev/null
@@ -1,34 +0,0 @@
-// Copyright 2024 The Autoware Contributors
-//
-// 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.
-
-#include "mrm_goal.hpp"
-
-namespace rviz_plugins
-{
-
-MrmGoalTool::MrmGoalTool()
-{
- shortcut_key_ = 'm';
-}
-
-void MrmGoalTool::onInitialize()
-{
- GoalTool::onInitialize();
- setName("MRM Goal Pose");
-}
-
-} // namespace rviz_plugins
-
-#include
-PLUGINLIB_EXPORT_CLASS(rviz_plugins::MrmGoalTool, rviz_common::Tool)
diff --git a/common/mission_planner_rviz_plugin/src/mrm_goal.hpp b/common/mission_planner_rviz_plugin/src/mrm_goal.hpp
deleted file mode 100644
index e16b0abf0bab3..0000000000000
--- a/common/mission_planner_rviz_plugin/src/mrm_goal.hpp
+++ /dev/null
@@ -1,34 +0,0 @@
-// Copyright 2024 The Autoware Contributors
-//
-// 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 MRM_GOAL_HPP_
-#define MRM_GOAL_HPP_
-
-#include
-
-namespace rviz_plugins
-{
-
-class MrmGoalTool : public rviz_default_plugins::tools::GoalTool
-{
- Q_OBJECT
-
-public:
- MrmGoalTool();
- void onInitialize() override;
-};
-
-} // namespace rviz_plugins
-
-#endif // MRM_GOAL_HPP_
diff --git a/common/mission_planner_rviz_plugin/src/route_selector_panel.cpp b/common/mission_planner_rviz_plugin/src/route_selector_panel.cpp
deleted file mode 100644
index b4b376b1e76ec..0000000000000
--- a/common/mission_planner_rviz_plugin/src/route_selector_panel.cpp
+++ /dev/null
@@ -1,148 +0,0 @@
-// Copyright 2024 The Autoware Contributors
-//
-// 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.
-
-#include "route_selector_panel.hpp"
-
-#include
-#include
-
-#include
-#include
-
-namespace rviz_plugins
-{
-
-QString to_string_state(const RouteState & state)
-{
- // clang-format off
- switch (state.state) {
- case RouteState::UNKNOWN: return "unknown";
- case RouteState::INITIALIZING: return "initializing";
- case RouteState::UNSET: return "unset";
- case RouteState::ROUTING: return "routing";
- case RouteState::SET: return "set";
- case RouteState::REROUTING: return "rerouting";
- case RouteState::ARRIVED: return "arrived";
- case RouteState::ABORTED: return "aborted";
- case RouteState::INTERRUPTED: return "interrupted";
- default: return "-----";
- }
- // clang-format on
-}
-
-RouteSelectorPanel::RouteSelectorPanel(QWidget * parent) : rviz_common::Panel(parent)
-{
- main_state_ = new QLabel("unknown");
- main_clear_ = new QPushButton("clear");
- mrm_state_ = new QLabel("unknown");
- mrm_clear_ = new QPushButton("clear");
- planner_state_ = new QLabel("unknown");
-
- connect(main_clear_, &QPushButton::clicked, this, &RouteSelectorPanel::onMainClear);
- connect(mrm_clear_, &QPushButton::clicked, this, &RouteSelectorPanel::onMrmClear);
-
- const auto layout = new QGridLayout();
- setLayout(layout);
- layout->addWidget(new QLabel("main"), 0, 0);
- layout->addWidget(main_state_, 0, 1);
- layout->addWidget(main_clear_, 0, 2);
- layout->addWidget(new QLabel("mrm"), 1, 0);
- layout->addWidget(mrm_state_, 1, 1);
- layout->addWidget(mrm_clear_, 1, 2);
- layout->addWidget(new QLabel("planner"), 2, 0);
- layout->addWidget(planner_state_, 2, 1);
-}
-
-void RouteSelectorPanel::onInitialize()
-{
- auto lock = getDisplayContext()->getRosNodeAbstraction().lock();
- auto node = lock->get_raw_node();
-
- const auto durable_qos = rclcpp::QoS(1).transient_local();
-
- sub_main_goal_ = node->create_subscription(
- "/rviz/route_selector/main/goal", rclcpp::QoS(1),
- std::bind(&RouteSelectorPanel::onMainGoal, this, std::placeholders::_1));
- sub_mrm_goal_ = node->create_subscription(
- "/rviz/route_selector/mrm/goal", rclcpp::QoS(1),
- std::bind(&RouteSelectorPanel::onMrmGoal, this, std::placeholders::_1));
- sub_main_state_ = node->create_subscription(
- "/planning/mission_planning/route_selector/main/state", durable_qos,
- std::bind(&RouteSelectorPanel::onMainState, this, std::placeholders::_1));
- sub_mrm_state_ = node->create_subscription(
- "/planning/mission_planning/route_selector/mrm/state", durable_qos,
- std::bind(&RouteSelectorPanel::onMrmState, this, std::placeholders::_1));
- sub_planner_state_ = node->create_subscription(
- "/planning/mission_planning/state", durable_qos,
- std::bind(&RouteSelectorPanel::onPlannerState, this, std::placeholders::_1));
-
- cli_main_clear_ =
- node->create_client("/planning/mission_planning/route_selector/main/clear_route");
- cli_mrm_clear_ =
- node->create_client("/planning/mission_planning/route_selector/mrm/clear_route");
- cli_main_set_waypoint_ = node->create_client(
- "/planning/mission_planning/route_selector/main/set_waypoint_route");
- cli_mrm_set_waypoint_ = node->create_client(
- "/planning/mission_planning/route_selector/mrm/set_waypoint_route");
-}
-
-void RouteSelectorPanel::onMainGoal(const PoseStamped::ConstSharedPtr msg)
-{
- const auto req = std::make_shared();
- req->header = msg->header;
- req->goal_pose = msg->pose;
- req->allow_modification = true;
- cli_main_set_waypoint_->async_send_request(req);
-}
-
-void RouteSelectorPanel::onMrmGoal(const PoseStamped::ConstSharedPtr msg)
-{
- const auto req = std::make_shared();
- req->header = msg->header;
- req->goal_pose = msg->pose;
- req->allow_modification = true;
- cli_mrm_set_waypoint_->async_send_request(req);
-}
-
-void RouteSelectorPanel::onMainState(RouteState::ConstSharedPtr msg)
-{
- main_state_->setText(to_string_state(*msg));
-}
-
-void RouteSelectorPanel::onMrmState(RouteState::ConstSharedPtr msg)
-{
- mrm_state_->setText(to_string_state(*msg));
-}
-
-void RouteSelectorPanel::onPlannerState(RouteState::ConstSharedPtr msg)
-{
- planner_state_->setText(to_string_state(*msg));
-}
-
-void RouteSelectorPanel::onMainClear()
-{
- const auto req = std::make_shared();
- cli_main_clear_->async_send_request(req);
-}
-
-void RouteSelectorPanel::onMrmClear()
-{
- const auto req = std::make_shared();
- cli_mrm_clear_->async_send_request(req);
-}
-
-} // namespace rviz_plugins
-
-#include
-PLUGINLIB_EXPORT_CLASS(rviz_plugins::RouteSelectorPanel, rviz_common::Panel)
diff --git a/common/mission_planner_rviz_plugin/src/route_selector_panel.hpp b/common/mission_planner_rviz_plugin/src/route_selector_panel.hpp
deleted file mode 100644
index 99101730661e0..0000000000000
--- a/common/mission_planner_rviz_plugin/src/route_selector_panel.hpp
+++ /dev/null
@@ -1,75 +0,0 @@
-// Copyright 2024 The Autoware Contributors
-//
-// 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 ROUTE_SELECTOR_PANEL_HPP_
-#define ROUTE_SELECTOR_PANEL_HPP_
-
-#include
-#include
-#include
-#include
-
-#include
-#include
-#include
-#include
-
-namespace rviz_plugins
-{
-
-using geometry_msgs::msg::PoseStamped;
-using tier4_planning_msgs::msg::RouteState;
-using tier4_planning_msgs::srv::ClearRoute;
-using tier4_planning_msgs::srv::SetWaypointRoute;
-
-class RouteSelectorPanel : public rviz_common::Panel
-{
- Q_OBJECT
-
-public:
- explicit RouteSelectorPanel(QWidget * parent = nullptr);
- void onInitialize() override;
-
-private:
- QLabel * main_state_;
- QLabel * mrm_state_;
- QLabel * planner_state_;
- QPushButton * main_clear_;
- QPushButton * mrm_clear_;
-
- rclcpp::Subscription::SharedPtr sub_main_goal_;
- rclcpp::Subscription::SharedPtr sub_mrm_goal_;
- void onMainGoal(const PoseStamped::ConstSharedPtr msg);
- void onMrmGoal(const PoseStamped::ConstSharedPtr msg);
-
- rclcpp::Subscription::SharedPtr sub_main_state_;
- rclcpp::Subscription::SharedPtr sub_mrm_state_;
- rclcpp::Subscription::SharedPtr sub_planner_state_;
- void onMainState(RouteState::ConstSharedPtr msg);
- void onMrmState(RouteState::ConstSharedPtr msg);
- void onPlannerState(RouteState::ConstSharedPtr msg);
-
- rclcpp::Client::SharedPtr cli_main_clear_;
- rclcpp::Client::SharedPtr cli_mrm_clear_;
- rclcpp::Client::SharedPtr cli_main_set_waypoint_;
- rclcpp::Client::SharedPtr cli_mrm_set_waypoint_;
-
-private Q_SLOTS:
- void onMainClear();
- void onMrmClear();
-};
-
-} // namespace rviz_plugins
-
-#endif // ROUTE_SELECTOR_PANEL_HPP_
diff --git a/common/motion_utils/include/motion_utils/resample/resample_utils.hpp b/common/motion_utils/include/motion_utils/resample/resample_utils.hpp
index 8bb5f13e3fb78..fb151ec56b085 100644
--- a/common/motion_utils/include/motion_utils/resample/resample_utils.hpp
+++ b/common/motion_utils/include/motion_utils/resample/resample_utils.hpp
@@ -27,7 +27,11 @@ namespace resample_utils
{
constexpr double close_s_threshold = 1e-6;
-#define log_error(message) std::cerr << "\033[31m " << message << " \033[0m" << std::endl;
+static inline rclcpp::Logger get_logger()
+{
+ constexpr const char * logger{"motion_utils.resample_utils"};
+ return rclcpp::get_logger(logger);
+}
template
bool validate_size(const T & points)
@@ -62,27 +66,27 @@ bool validate_arguments(const T & input_points, const std::vector & resa
{
// Check size of the arguments
if (!validate_size(input_points)) {
- log_error("[resample_utils] invalid argument: The number of input points is less than 2");
+ RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2");
tier4_autoware_utils::print_backtrace();
return false;
}
if (!validate_size(resampling_intervals)) {
- log_error(
- "[resample_utils] invalid argument: The number of resampling intervals is less than 2");
+ RCLCPP_DEBUG(
+ get_logger(), "invalid argument: The number of resampling intervals is less than 2");
tier4_autoware_utils::print_backtrace();
return false;
}
// Check resampling range
if (!validate_resampling_range(input_points, resampling_intervals)) {
- log_error("[resample_utils] invalid argument: resampling interval is longer than input points");
+ RCLCPP_DEBUG(get_logger(), "invalid argument: resampling interval is longer than input points");
tier4_autoware_utils::print_backtrace();
return false;
}
// Check duplication
if (!validate_points_duplication(input_points)) {
- log_error("[resample_utils] invalid argument: input points has some duplicated points");
+ RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points");
tier4_autoware_utils::print_backtrace();
return false;
}
@@ -95,23 +99,23 @@ bool validate_arguments(const T & input_points, const double resampling_interval
{
// Check size of the arguments
if (!validate_size(input_points)) {
- log_error("[resample_utils] invalid argument: The number of input points is less than 2");
+ RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2");
tier4_autoware_utils::print_backtrace();
return false;
}
// check resampling interval
if (resampling_interval < motion_utils::overlap_threshold) {
- log_error(
- "[resample_utils] invalid argument: resampling interval is less than " +
- std::to_string(motion_utils::overlap_threshold));
+ RCLCPP_DEBUG(
+ get_logger(), "invalid argument: resampling interval is less than %f",
+ motion_utils::overlap_threshold);
tier4_autoware_utils::print_backtrace();
return false;
}
// Check duplication
if (!validate_points_duplication(input_points)) {
- log_error("[resample_utils] invalid argument: input points has some duplicated points");
+ RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points");
tier4_autoware_utils::print_backtrace();
return false;
}
diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp
index 45377ba18affd..c0ddd84cd2a30 100644
--- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp
+++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp
@@ -21,6 +21,7 @@
#include "tier4_autoware_utils/system/backtrace.hpp"
#include
+#include
#include
#include
@@ -33,9 +34,14 @@
#include
#include
#include
+
namespace motion_utils
{
-#define log_error(message) std::cerr << "\033[31m " << message << " \033[0m" << std::endl;
+static inline rclcpp::Logger get_logger()
+{
+ constexpr const char * logger{"motion_utils.trajectory"};
+ return rclcpp::get_logger(logger);
+}
/**
* @brief validate if points container is empty or not
@@ -213,7 +219,7 @@ std::optional searchZeroVelocityIndex(
try {
validateNonEmpty(points_with_twist);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return {};
}
@@ -245,7 +251,7 @@ std::optional searchZeroVelocityIndex(const T & points_with_twist, const
try {
validateNonEmpty(points_with_twist);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return {};
}
@@ -333,7 +339,7 @@ std::optional findNearestIndex(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return {};
}
@@ -406,9 +412,10 @@ double calcLongitudinalOffsetToSegment(
if (throw_exception) {
throw std::out_of_range(error_message);
}
- log_error(
- error_message +
- " Return NaN since no_throw option is enabled. The maintainer must check the code.");
+ RCLCPP_DEBUG(
+ get_logger(),
+ "%s Return NaN since no_throw option is enabled. The maintainer must check the code.",
+ error_message.c_str());
return std::nan("");
}
@@ -420,7 +427,7 @@ double calcLongitudinalOffsetToSegment(
try {
validateNonEmpty(overlap_removed_points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return std::nan("");
}
}
@@ -433,9 +440,10 @@ double calcLongitudinalOffsetToSegment(
if (throw_exception) {
throw std::runtime_error(error_message);
}
- log_error(
- error_message +
- " Return NaN since no_throw option is enabled. The maintainer must check the code.");
+ RCLCPP_DEBUG(
+ get_logger(),
+ "%s Return NaN since no_throw option is enabled. The maintainer must check the code.",
+ error_message.c_str());
return std::nan("");
}
@@ -578,9 +586,10 @@ double calcLateralOffset(
try {
validateNonEmpty(overlap_removed_points);
} catch (const std::exception & e) {
- log_error(
- std::string(e.what()) +
- " Return NaN since no_throw option is enabled. The maintainer must check the code.");
+ RCLCPP_DEBUG(
+ get_logger(),
+ "%s Return NaN since no_throw option is enabled. The maintainer must check the code.",
+ e.what());
return std::nan("");
}
}
@@ -593,9 +602,10 @@ double calcLateralOffset(
if (throw_exception) {
throw std::runtime_error(error_message);
}
- log_error(
- error_message +
- " Return NaN since no_throw option is enabled. The maintainer must check the code.");
+ RCLCPP_DEBUG(
+ get_logger(),
+ "%s Return NaN since no_throw option is enabled. The maintainer must check the code.",
+ error_message.c_str());
return std::nan("");
}
@@ -649,9 +659,10 @@ double calcLateralOffset(
try {
validateNonEmpty(overlap_removed_points);
} catch (const std::exception & e) {
- log_error(
- std::string(e.what()) +
- " Return NaN since no_throw option is enabled. The maintainer must check the code.");
+ RCLCPP_DEBUG(
+ get_logger(),
+ "%s Return NaN since no_throw option is enabled. The maintainer must check the code.",
+ e.what());
return std::nan("");
}
}
@@ -664,9 +675,10 @@ double calcLateralOffset(
if (throw_exception) {
throw std::runtime_error(error_message);
}
- log_error(
- error_message +
- " Return NaN since no_throw option is enabled. The maintainer must check the code.");
+ RCLCPP_DEBUG(
+ get_logger(),
+ "%s Return NaN since no_throw option is enabled. The maintainer must check the code.",
+ error_message.c_str());
return std::nan("");
}
@@ -701,7 +713,7 @@ double calcSignedArcLength(const T & points, const size_t src_idx, const size_t
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return 0.0;
}
@@ -743,7 +755,7 @@ std::vector calcSignedArcLengthPartialSum(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return {};
}
@@ -795,7 +807,7 @@ double calcSignedArcLength(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return 0.0;
}
@@ -837,7 +849,7 @@ double calcSignedArcLength(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return 0.0;
}
@@ -875,7 +887,7 @@ double calcSignedArcLength(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return 0.0;
}
@@ -914,7 +926,7 @@ double calcArcLength(const T & points)
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return 0.0;
}
@@ -1021,7 +1033,7 @@ std::optional calcDistanceToForwardStopPoint(
try {
validateNonEmpty(points_with_twist);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return {};
}
@@ -1055,7 +1067,7 @@ std::optional calcLongitudinalOffsetPoint(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return {};
}
@@ -1068,9 +1080,10 @@ std::optional calcLongitudinalOffsetPoint(
if (throw_exception) {
throw std::out_of_range(error_message);
}
- log_error(
- error_message +
- " Return NaN since no_throw option is enabled. The maintainer must check the code.");
+ RCLCPP_DEBUG(
+ get_logger(),
+ "%s Return NaN since no_throw option is enabled. The maintainer must check the code.",
+ error_message.c_str());
return {};
}
@@ -1137,7 +1150,7 @@ std::optional calcLongitudinalOffsetPoint(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error("Failed to calculate longitudinal offset: " + std::string(e.what()));
+ RCLCPP_DEBUG(get_logger(), "Failed to calculate longitudinal offset: %s", e.what());
return {};
}
@@ -1185,7 +1198,7 @@ std::optional calcLongitudinalOffsetPose(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error("Failed to calculate longitudinal offset: " + std::string(e.what()));
+ RCLCPP_DEBUG(get_logger(), "Failed to calculate longitudinal offset: %s", e.what());
return {};
}
@@ -1198,12 +1211,12 @@ std::optional calcLongitudinalOffsetPose(
if (throw_exception) {
throw std::out_of_range(error_message);
}
- log_error(error_message);
+ RCLCPP_DEBUG(get_logger(), "%s", error_message.c_str());
return {};
}
if (points.size() == 1) {
- log_error("Failed to calculate longitudinal offset: points size is one.");
+ RCLCPP_DEBUG(get_logger(), "Failed to calculate longitudinal offset: points size is one.");
return {};
}
@@ -1288,7 +1301,7 @@ std::optional calcLongitudinalOffsetPose(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return {};
}
@@ -1334,7 +1347,7 @@ std::optional insertTargetPoint(
try {
validateNonEmpty(points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return {};
}
@@ -1349,7 +1362,7 @@ std::optional insertTargetPoint(
try {
validateNonSharpAngle(p_front, p_target, p_back);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return {};
}
@@ -2210,7 +2223,7 @@ std::optional calcDistanceToForwardStopPoint(
try {
validateNonEmpty(points_with_twist);
} catch (const std::exception & e) {
- log_error("Failed to calculate stop distance" + std::string(e.what()));
+ RCLCPP_DEBUG(get_logger(), "Failed to calculate stop distance %s", e.what());
return {};
}
@@ -2349,7 +2362,7 @@ T cropPoints(
cropped_forward_points, target_pos, modified_target_seg_idx, backward_length);
if (cropped_points.size() < 2) {
- log_error("Return original points since cropped_points size is less than 2.");
+ RCLCPP_DEBUG(get_logger(), "Return original points since cropped_points size is less than 2.");
return points;
}
@@ -2394,7 +2407,7 @@ double calcYawDeviation(
try {
validateNonEmpty(overlap_removed_points);
} catch (const std::exception & e) {
- log_error(e.what());
+ RCLCPP_DEBUG(get_logger(), "%s", e.what());
return 0.0;
}
}
@@ -2407,9 +2420,10 @@ double calcYawDeviation(
if (throw_exception) {
throw std::runtime_error(error_message);
}
- log_error(
- error_message +
- " Return 0 since no_throw option is enabled. The maintainer must check the code.");
+ RCLCPP_DEBUG(
+ get_logger(),
+ "%s Return 0 since no_throw option is enabled. The maintainer must check the code.",
+ error_message.c_str());
return 0.0;
}
diff --git a/common/motion_utils/test/src/trajectory/test_trajectory.cpp b/common/motion_utils/test/src/trajectory/test_trajectory.cpp
index f66297c6df867..326b6e106e30b 100644
--- a/common/motion_utils/test/src/trajectory/test_trajectory.cpp
+++ b/common/motion_utils/test/src/trajectory/test_trajectory.cpp
@@ -1876,40 +1876,34 @@ TEST(trajectory, insertTargetPoint)
// Invalid target point(In front of begin point)
{
- testing::internal::CaptureStderr();
auto traj_out = traj;
const auto p_target = createPoint(-1.0, 0.0, 0.0);
const size_t base_idx = findNearestSegmentIndex(traj.points, p_target);
const auto insert_idx = insertTargetPoint(base_idx, p_target, traj_out.points);
- EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle"), std::string::npos);
EXPECT_EQ(insert_idx, std::nullopt);
}
// Invalid target point(Behind of end point)
{
- testing::internal::CaptureStderr();
auto traj_out = traj;
const auto p_target = createPoint(10.0, 0.0, 0.0);
const size_t base_idx = findNearestSegmentIndex(traj.points, p_target);
const auto insert_idx = insertTargetPoint(base_idx, p_target, traj_out.points);
- EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle"), std::string::npos);
EXPECT_EQ(insert_idx, std::nullopt);
}
// Invalid target point(Huge lateral offset)
{
- testing::internal::CaptureStderr();
auto traj_out = traj;
const auto p_target = createPoint(4.0, 10.0, 0.0);
const size_t base_idx = findNearestSegmentIndex(traj.points, p_target);
const auto insert_idx = insertTargetPoint(base_idx, p_target, traj_out.points);
- EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle"), std::string::npos);
EXPECT_EQ(insert_idx, std::nullopt);
}
@@ -2304,13 +2298,11 @@ TEST(trajectory, insertTargetPoint_Length)
// Invalid target point(Huge lateral offset)
{
- testing::internal::CaptureStderr();
auto traj_out = traj;
const auto p_target = createPoint(4.0, 10.0, 0.0);
const auto insert_idx = insertTargetPoint(4.0, p_target, traj_out.points);
- EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos);
EXPECT_EQ(insert_idx, std::nullopt);
}
@@ -4310,40 +4302,34 @@ TEST(trajectory, insertStopPoint_with_pose_and_segment_index)
// Invalid target point(In front of begin point)
{
- testing::internal::CaptureStderr();
auto traj_out = traj;
const auto p_target = createPoint(-1.0, 0.0, 0.0);
const size_t base_idx = findNearestSegmentIndex(traj.points, p_target);
const auto insert_idx = insertStopPoint(base_idx, p_target, traj_out.points);
- EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos);
EXPECT_EQ(insert_idx, std::nullopt);
}
// Invalid target point(Behind of end point)
{
- testing::internal::CaptureStderr();
auto traj_out = traj;
const auto p_target = createPoint(10.0, 0.0, 0.0);
const size_t base_idx = findNearestSegmentIndex(traj.points, p_target);
const auto insert_idx = insertStopPoint(base_idx, p_target, traj_out.points);
- EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos);
EXPECT_EQ(insert_idx, std::nullopt);
}
// Invalid target point(Huge lateral offset)
{
- testing::internal::CaptureStderr();
auto traj_out = traj;
const auto p_target = createPoint(4.0, 10.0, 0.0);
const size_t base_idx = findNearestSegmentIndex(traj.points, p_target);
const auto insert_idx = insertStopPoint(base_idx, p_target, traj_out.points);
- EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos);
EXPECT_EQ(insert_idx, std::nullopt);
}
diff --git a/common/rtc_manager_rviz_plugin/CMakeLists.txt b/common/rtc_manager_rviz_plugin/CMakeLists.txt
deleted file mode 100644
index f2fad9e24665f..0000000000000
--- a/common/rtc_manager_rviz_plugin/CMakeLists.txt
+++ /dev/null
@@ -1,28 +0,0 @@
-cmake_minimum_required(VERSION 3.14)
-project(rtc_manager_rviz_plugin)
-
-find_package(autoware_cmake REQUIRED)
-autoware_package()
-
-find_package(Qt5 REQUIRED Core Widgets)
-set(QT_LIBRARIES Qt5::Widgets)
-set(CMAKE_AUTOMOC ON)
-set(CMAKE_INCLUDE_CURRENT_DIR ON)
-add_definitions(-DQT_NO_KEYWORDS)
-
-ament_auto_add_library(${PROJECT_NAME} SHARED
- src/rtc_manager_panel.cpp
-)
-
-target_link_libraries(${PROJECT_NAME}
- ${QT_LIBRARIES}
-)
-
-# Export the plugin to be imported by rviz2
-pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml)
-
-ament_auto_package(
- INSTALL_TO_SHARE
- icons
- plugins
-)
diff --git a/common/rtc_manager_rviz_plugin/README.md b/common/rtc_manager_rviz_plugin/README.md
deleted file mode 100644
index 7a15d56fe235a..0000000000000
--- a/common/rtc_manager_rviz_plugin/README.md
+++ /dev/null
@@ -1,36 +0,0 @@
-# rtc_manager_rviz_plugin
-
-## Purpose
-
-The purpose of this Rviz plugin is
-
-1. To display each content of RTC status.
-
-2. To switch each module of RTC auto mode.
-
-3. To change RTC cooperate commands by button.
-
-![rtc_manager_panel](./images/rtc_manager_panel.png)
-
-## Inputs / Outputs
-
-### Input
-
-| Name | Type | Description |
-| ------------------------------ | ------------------------------------------- | --------------------------------------- |
-| `/api/external/get/rtc_status` | `tier4_rtc_msgs::msg::CooperateStatusArray` | The statuses of each Cooperate Commands |
-
-### Output
-
-| Name | Type | Description |
-| -------------------------------- | ---------------------------------------- | ---------------------------------------------------- |
-| `/api/external/set/rtc_commands` | `tier4_rtc_msgs::src::CooperateCommands` | The Cooperate Commands for each planning |
-| `/planning/enable_auto_mode/*` | `tier4_rtc_msgs::src::AutoMode` | The Cooperate Commands mode for each planning module |
-
-## HowToUse
-
-1. Start rviz and select panels/Add new panel.
- ![select_panel](./images/select_panels.png)
-
-2. tier4_state_rviz_plugin/RTCManagerPanel and press OK.
- ![select_rtc_panel](./images/rtc_selection.png)
diff --git a/common/rtc_manager_rviz_plugin/icons/classes/RTCManagerPanel.png b/common/rtc_manager_rviz_plugin/icons/classes/RTCManagerPanel.png
deleted file mode 100644
index 6a67573717ae1..0000000000000
Binary files a/common/rtc_manager_rviz_plugin/icons/classes/RTCManagerPanel.png and /dev/null differ
diff --git a/common/rtc_manager_rviz_plugin/images/rtc_manager_panel.png b/common/rtc_manager_rviz_plugin/images/rtc_manager_panel.png
deleted file mode 100644
index 36c1b4760308b..0000000000000
Binary files a/common/rtc_manager_rviz_plugin/images/rtc_manager_panel.png and /dev/null differ
diff --git a/common/rtc_manager_rviz_plugin/images/rtc_selection.png b/common/rtc_manager_rviz_plugin/images/rtc_selection.png
deleted file mode 100644
index f9c5d120bdd70..0000000000000
Binary files a/common/rtc_manager_rviz_plugin/images/rtc_selection.png and /dev/null differ
diff --git a/common/rtc_manager_rviz_plugin/images/select_panels.png b/common/rtc_manager_rviz_plugin/images/select_panels.png
deleted file mode 100644
index a691602c42c3c..0000000000000
Binary files a/common/rtc_manager_rviz_plugin/images/select_panels.png and /dev/null differ
diff --git a/common/rtc_manager_rviz_plugin/package.xml b/common/rtc_manager_rviz_plugin/package.xml
deleted file mode 100644
index 53f00386bdb4d..0000000000000
--- a/common/rtc_manager_rviz_plugin/package.xml
+++ /dev/null
@@ -1,33 +0,0 @@
-
-
-
- rtc_manager_rviz_plugin
- 0.0.0
- The rtc manager rviz plugin package
- Taiki Tanaka
- Tomoya Kimura
-
- Apache License 2.0
-
- ament_cmake_auto
- autoware_cmake
-
- libqt5-core
- libqt5-gui
- libqt5-widgets
- qtbase5-dev
- rclcpp
- rviz_common
- tier4_external_api_msgs
- tier4_planning_msgs
- tier4_rtc_msgs
- unique_identifier_msgs
-
- ament_lint_auto
- autoware_lint_common
-
-
- ament_cmake
-
-
-
diff --git a/common/rtc_manager_rviz_plugin/plugins/plugin_description.xml b/common/rtc_manager_rviz_plugin/plugins/plugin_description.xml
deleted file mode 100644
index 001ae153e6762..0000000000000
--- a/common/rtc_manager_rviz_plugin/plugins/plugin_description.xml
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
-
- RTCManagerPanel
-
-
-
diff --git a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp
deleted file mode 100644
index 058a5d5deb5d6..0000000000000
--- a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp
+++ /dev/null
@@ -1,474 +0,0 @@
-//
-// Copyright 2020 Tier IV, Inc. All rights reserved.
-//
-// 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.
-//
-
-#include "rtc_manager_panel.hpp"
-
-#include
-#include
-#include
-#include
-
-#include
-
-namespace rviz_plugins
-{
-inline std::string Bool2String(const bool var)
-{
- return var ? "True" : "False";
-}
-inline bool uint2bool(uint8_t var)
-{
- return var == static_cast(0) ? false : true;
-}
-using std::placeholders::_1;
-using std::placeholders::_2;
-
-std::string getModuleName(const uint8_t module_type)
-{
- switch (module_type) {
- case Module::LANE_CHANGE_LEFT: {
- return "lane_change_left";
- }
- case Module::LANE_CHANGE_RIGHT: {
- return "lane_change_right";
- }
- case Module::EXT_REQUEST_LANE_CHANGE_LEFT: {
- return "external_request_lane_change_left";
- }
- case Module::EXT_REQUEST_LANE_CHANGE_RIGHT: {
- return "external_request_lane_change_right";
- }
- case Module::AVOIDANCE_BY_LC_LEFT: {
- return "avoidance_by_lane_change_left";
- }
- case Module::AVOIDANCE_BY_LC_RIGHT: {
- return "avoidance_by_lane_change_right";
- }
- case Module::AVOIDANCE_LEFT: {
- return "avoidance_left";
- }
- case Module::AVOIDANCE_RIGHT: {
- return "avoidance_right";
- }
- case Module::GOAL_PLANNER: {
- return "goal_planner";
- }
- case Module::START_PLANNER: {
- return "start_planner";
- }
- case Module::TRAFFIC_LIGHT: {
- return "traffic_light";
- }
- case Module::INTERSECTION: {
- return "intersection";
- }
- case Module::CROSSWALK: {
- return "crosswalk";
- }
- case Module::BLIND_SPOT: {
- return "blind_spot";
- }
- case Module::DETECTION_AREA: {
- return "detection_area";
- }
- case Module::NO_STOPPING_AREA: {
- return "no_stopping_area";
- }
- case Module::OCCLUSION_SPOT: {
- return "occlusion_spot";
- }
- case Module::INTERSECTION_OCCLUSION: {
- return "intersection_occlusion";
- }
- }
- return "NONE";
-}
-
-bool isPathChangeModule(const uint8_t module_type)
-{
- if (
- module_type == Module::LANE_CHANGE_LEFT || module_type == Module::LANE_CHANGE_RIGHT ||
- module_type == Module::EXT_REQUEST_LANE_CHANGE_LEFT ||
- module_type == Module::EXT_REQUEST_LANE_CHANGE_RIGHT ||
- module_type == Module::AVOIDANCE_BY_LC_LEFT || module_type == Module::AVOIDANCE_BY_LC_RIGHT ||
- module_type == Module::AVOIDANCE_LEFT || module_type == Module::AVOIDANCE_RIGHT ||
- module_type == Module::GOAL_PLANNER || module_type == Module::START_PLANNER) {
- return true;
- }
- return false;
-}
-
-RTCManagerPanel::RTCManagerPanel(QWidget * parent) : rviz_common::Panel(parent)
-{
- // TODO(tanaka): replace this magic number to Module::SIZE
- const size_t module_size = 19;
- auto_modes_.reserve(module_size);
- auto * v_layout = new QVBoxLayout;
- auto vertical_header = new QHeaderView(Qt::Vertical);
- vertical_header->hide();
- auto horizontal_header = new QHeaderView(Qt::Horizontal);
- horizontal_header->setSectionResizeMode(QHeaderView::Stretch);
- auto_mode_table_ = new QTableWidget();
- auto_mode_table_->setColumnCount(4);
- auto_mode_table_->setHorizontalHeaderLabels(
- {"Module", "ToAutoMode", "ToManualMode", "ApprovalMode"});
- auto_mode_table_->setVerticalHeader(vertical_header);
- auto_mode_table_->setHorizontalHeader(horizontal_header);
- const size_t num_modules = module_size;
- auto_mode_table_->setRowCount(num_modules);
- for (size_t i = 0; i < num_modules; i++) {
- auto * rtc_auto_mode = new RTCAutoMode();
- rtc_auto_mode->setParent(this);
- // module
- {
- const uint8_t module_type = static_cast(i);
- rtc_auto_mode->module_name = getModuleName(module_type);
- std::string module_name = rtc_auto_mode->module_name;
- auto label = new QLabel(QString::fromStdString(module_name));
- label->setAlignment(Qt::AlignCenter);
- label->setText(QString::fromStdString(module_name));
- if (isPathChangeModule(module_type))
- label->setStyleSheet(BG_PURPLE);
- else
- label->setStyleSheet(BG_ORANGE);
- auto_mode_table_->setCellWidget(i, 0, label);
- }
- // mode button
- {
- // auto mode button
- rtc_auto_mode->auto_module_button_ptr = new QPushButton("auto mode");
- rtc_auto_mode->auto_module_button_ptr->setCheckable(true);
- connect(
- rtc_auto_mode->auto_module_button_ptr, &QPushButton::clicked, rtc_auto_mode,
- &RTCAutoMode::onChangeToAutoMode);
- auto_mode_table_->setCellWidget(i, 1, rtc_auto_mode->auto_module_button_ptr);
- // manual mode button
- rtc_auto_mode->manual_module_button_ptr = new QPushButton("manual mode");
- rtc_auto_mode->manual_module_button_ptr->setCheckable(true);
- connect(
- rtc_auto_mode->manual_module_button_ptr, &QPushButton::clicked, rtc_auto_mode,
- &RTCAutoMode::onChangeToManualMode);
- auto_mode_table_->setCellWidget(i, 2, rtc_auto_mode->manual_module_button_ptr);
- }
- // current mode
- {
- QString mode = QString::fromStdString("INIT");
- rtc_auto_mode->auto_manual_mode_label = new QLabel(mode);
- rtc_auto_mode->auto_manual_mode_label->setAlignment(Qt::AlignCenter);
- rtc_auto_mode->auto_manual_mode_label->setText(mode);
- auto_mode_table_->setCellWidget(i, 3, rtc_auto_mode->auto_manual_mode_label);
- }
- auto_modes_.emplace_back(rtc_auto_mode);
- }
- v_layout->addWidget(auto_mode_table_);
-
- num_rtc_status_ptr_ = new QLabel("Init");
- v_layout->addWidget(num_rtc_status_ptr_);
-
- // lateral execution
- auto * exe_path_change_layout = new QHBoxLayout;
- {
- exec_path_change_button_ptr_ = new QPushButton("Execute Path Change");
- exec_path_change_button_ptr_->setCheckable(false);
- exec_path_change_button_ptr_->setStyleSheet(BG_PURPLE);
- connect(
- exec_path_change_button_ptr_, &QPushButton::clicked, this,
- &RTCManagerPanel::onClickExecutePathChange);
- exe_path_change_layout->addWidget(exec_path_change_button_ptr_);
- wait_path_change_button_ptr_ = new QPushButton("Wait Path Change");
- wait_path_change_button_ptr_->setCheckable(false);
- wait_path_change_button_ptr_->setStyleSheet(BG_PURPLE);
- connect(
- wait_path_change_button_ptr_, &QPushButton::clicked, this,
- &RTCManagerPanel::onClickWaitPathChange);
- exe_path_change_layout->addWidget(wait_path_change_button_ptr_);
- }
- v_layout->addLayout(exe_path_change_layout);
-
- // longitudinal execution
- auto * exe_vel_change_layout = new QHBoxLayout;
- {
- exec_vel_change_button_ptr_ = new QPushButton("Execute Velocity Change");
- exec_vel_change_button_ptr_->setCheckable(false);
- exec_vel_change_button_ptr_->setStyleSheet(BG_ORANGE);
- connect(
- exec_vel_change_button_ptr_, &QPushButton::clicked, this,
- &RTCManagerPanel::onClickExecuteVelChange);
- exe_vel_change_layout->addWidget(exec_vel_change_button_ptr_);
- wait_vel_change_button_ptr_ = new QPushButton("Wait Velocity Change");
- wait_vel_change_button_ptr_->setCheckable(false);
- wait_vel_change_button_ptr_->setStyleSheet(BG_ORANGE);
- connect(
- wait_vel_change_button_ptr_, &QPushButton::clicked, this,
- &RTCManagerPanel::onClickWaitVelChange);
- exe_vel_change_layout->addWidget(wait_vel_change_button_ptr_);
- }
- v_layout->addLayout(exe_vel_change_layout);
-
- // execution
- auto * rtc_exe_layout = new QHBoxLayout;
- {
- exec_button_ptr_ = new QPushButton("Execute All");
- exec_button_ptr_->setCheckable(false);
- connect(exec_button_ptr_, &QPushButton::clicked, this, &RTCManagerPanel::onClickExecution);
- rtc_exe_layout->addWidget(exec_button_ptr_);
- wait_button_ptr_ = new QPushButton("Wait All");
- wait_button_ptr_->setCheckable(false);
- connect(wait_button_ptr_, &QPushButton::clicked, this, &RTCManagerPanel::onClickWait);
- rtc_exe_layout->addWidget(wait_button_ptr_);
- }
- v_layout->addLayout(rtc_exe_layout);
-
- // statuses
- auto * rtc_table_layout = new QHBoxLayout;
- {
- auto vertical_header = new QHeaderView(Qt::Vertical);
- vertical_header->hide();
- auto horizontal_header = new QHeaderView(Qt::Horizontal);
- horizontal_header->setSectionResizeMode(QHeaderView::Stretch);
- rtc_table_ = new QTableWidget();
- rtc_table_->setColumnCount(column_size_);
- rtc_table_->setHorizontalHeaderLabels(
- {"ID", "Module", "AW Safe", "Received Cmd", "AutoMode", "StartDistance", "FinishDistance"});
- rtc_table_->setVerticalHeader(vertical_header);
- rtc_table_->setHorizontalHeader(horizontal_header);
- rtc_table_layout->addWidget(rtc_table_);
- v_layout->addLayout(rtc_table_layout);
- }
- setLayout(v_layout);
-}
-
-void RTCManagerPanel::onInitialize()
-{
- raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();
-
- client_rtc_commands_ =
- raw_node_->create_client("/api/external/set/rtc_commands");
-
- for (size_t i = 0; i < auto_modes_.size(); i++) {
- auto & a = auto_modes_.at(i);
- // auto mode
- a->enable_auto_mode_cli =
- raw_node_->create_client(enable_auto_mode_namespace_ + "/" + a->module_name);
- }
-
- sub_rtc_status_ = raw_node_->create_subscription(
- "/api/external/get/rtc_status", 1, std::bind(&RTCManagerPanel::onRTCStatus, this, _1));
-}
-
-void RTCAutoMode::onChangeToAutoMode()
-{
- AutoMode::Request::SharedPtr request = std::make_shared();
- request->enable = true;
- enable_auto_mode_cli->async_send_request(request);
- auto_manual_mode_label->setText("AutoMode");
- auto_manual_mode_label->setStyleSheet(BG_BLUE);
- auto_module_button_ptr->setChecked(true);
- manual_module_button_ptr->setChecked(false);
-}
-
-void RTCAutoMode::onChangeToManualMode()
-{
- AutoMode::Request::SharedPtr request = std::make_shared();
- request->enable = false;
- enable_auto_mode_cli->async_send_request(request);
- auto_manual_mode_label->setText("ManualMode");
- auto_manual_mode_label->setStyleSheet(BG_YELLOW);
- manual_module_button_ptr->setChecked(true);
- auto_module_button_ptr->setChecked(false);
-}
-
-CooperateCommand setRTCCommandFromStatus(CooperateStatus & status)
-{
- CooperateCommand cooperate_command;
- cooperate_command.uuid = status.uuid;
- cooperate_command.module = status.module;
- cooperate_command.command = status.command_status;
- return cooperate_command;
-}
-
-void RTCManagerPanel::onClickChangeRequest(const bool is_path_change, const uint8_t command)
-{
- if (!cooperate_statuses_ptr_) return;
- if (cooperate_statuses_ptr_->statuses.empty()) return;
- auto executable_cooperate_commands_request = std::make_shared();
- executable_cooperate_commands_request->stamp = cooperate_statuses_ptr_->stamp;
- // send coop request
- for (auto status : cooperate_statuses_ptr_->statuses) {
- if (is_path_change ^ isPathChangeModule(status.module.type)) continue;
- CooperateCommand cooperate_command = setRTCCommandFromStatus(status);
- cooperate_command.command.type = command;
- executable_cooperate_commands_request->commands.emplace_back(cooperate_command);
- // To consider needs to change path step by step
- if (is_path_change && !status.auto_mode && status.command_status.type ^ command) {
- break;
- }
- }
- client_rtc_commands_->async_send_request(executable_cooperate_commands_request);
-}
-
-void RTCManagerPanel::onClickCommandRequest(const uint8_t command)
-{
- if (!cooperate_statuses_ptr_) return;
- if (cooperate_statuses_ptr_->statuses.empty()) return;
- auto executable_cooperate_commands_request = std::make_shared();
- executable_cooperate_commands_request->stamp = cooperate_statuses_ptr_->stamp;
- // send coop request
- for (auto status : cooperate_statuses_ptr_->statuses) {
- CooperateCommand cooperate_command = setRTCCommandFromStatus(status);
- cooperate_command.command.type = command;
- executable_cooperate_commands_request->commands.emplace_back(cooperate_command);
- }
- client_rtc_commands_->async_send_request(executable_cooperate_commands_request);
-}
-
-void RTCManagerPanel::onClickExecuteVelChange()
-{
- onClickChangeRequest(false, Command::ACTIVATE);
-}
-void RTCManagerPanel::onClickWaitVelChange()
-{
- onClickChangeRequest(false, Command::DEACTIVATE);
-}
-void RTCManagerPanel::onClickExecutePathChange()
-{
- onClickChangeRequest(true, Command::ACTIVATE);
-}
-void RTCManagerPanel::onClickWaitPathChange()
-{
- onClickChangeRequest(true, Command::DEACTIVATE);
-}
-void RTCManagerPanel::onClickExecution()
-{
- onClickCommandRequest(Command::ACTIVATE);
-}
-void RTCManagerPanel::onClickWait()
-{
- onClickCommandRequest(Command::DEACTIVATE);
-}
-
-void RTCManagerPanel::onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg)
-{
- cooperate_statuses_ptr_ = std::make_shared(*msg);
- rtc_table_->clearContents();
- num_rtc_status_ptr_->setText(
- QString::fromStdString("The Number of RTC Statuses: " + std::to_string(msg->statuses.size())));
- if (msg->statuses.empty()) {
- rtc_table_->update();
- return;
- }
- // this is to stable rtc display not to occupy too much
- size_t min_display_size{5};
- size_t max_display_size{10};
- // rtc messages are already sorted by distance
- rtc_table_->setRowCount(
- std::max(min_display_size, std::min(msg->statuses.size(), max_display_size)));
- int cnt = 0;
-
- auto sorted_statuses = msg->statuses;
- std::partition(sorted_statuses.begin(), sorted_statuses.end(), [](const auto & status) {
- return !status.auto_mode && !uint2bool(status.command_status.type);
- });
-
- for (auto status : sorted_statuses) {
- if (static_cast(cnt) >= max_display_size) {
- rtc_table_->update();
- return;
- }
- // uuid
- {
- std::stringstream uuid;
- uuid << std::setw(4) << std::setfill('0') << static_cast(status.uuid.uuid.at(0));
- auto label = new QLabel(QString::fromStdString(uuid.str()));
- label->setAlignment(Qt::AlignCenter);
- label->setText(QString::fromStdString(uuid.str()));
- rtc_table_->setCellWidget(cnt, 0, label);
- }
-
- // module name
- {
- std::string module_name = getModuleName(status.module.type);
- auto label = new QLabel(QString::fromStdString(module_name));
- label->setAlignment(Qt::AlignCenter);
- label->setText(QString::fromStdString(module_name));
- rtc_table_->setCellWidget(cnt, 1, label);
- }
-
- // is aw safe
- bool is_aw_safe = status.safe;
- {
- std::string is_safe = Bool2String(is_aw_safe);
- auto label = new QLabel(QString::fromStdString(is_safe));
- label->setAlignment(Qt::AlignCenter);
- label->setText(QString::fromStdString(is_safe));
- rtc_table_->setCellWidget(cnt, 2, label);
- }
-
- // is operator safe
- const bool is_execute = uint2bool(status.command_status.type);
- {
- std::string text = is_execute ? "EXECUTE" : "WAIT";
- if (status.auto_mode) text = "NONE";
- auto label = new QLabel(QString::fromStdString(text));
- label->setAlignment(Qt::AlignCenter);
- label->setText(QString::fromStdString(text));
- rtc_table_->setCellWidget(cnt, 3, label);
- }
-
- // is auto mode
- const bool is_rtc_auto_mode = status.auto_mode;
- {
- std::string is_auto_mode = Bool2String(is_rtc_auto_mode);
- auto label = new QLabel(QString::fromStdString(is_auto_mode));
- label->setAlignment(Qt::AlignCenter);
- label->setText(QString::fromStdString(is_auto_mode));
- rtc_table_->setCellWidget(cnt, 4, label);
- }
-
- // start distance
- {
- std::string start_distance = std::to_string(status.start_distance);
- auto label = new QLabel(QString::fromStdString(start_distance));
- label->setAlignment(Qt::AlignCenter);
- label->setText(QString::fromStdString(start_distance));
- rtc_table_->setCellWidget(cnt, 5, label);
- }
-
- // finish distance
- {
- std::string finish_distance = std::to_string(status.finish_distance);
- auto label = new QLabel(QString::fromStdString(finish_distance));
- label->setAlignment(Qt::AlignCenter);
- label->setText(QString::fromStdString(finish_distance));
- rtc_table_->setCellWidget(cnt, 6, label);
- }
-
- // add color for recognition
- if (is_rtc_auto_mode || (is_aw_safe && is_execute)) {
- rtc_table_->cellWidget(cnt, 1)->setStyleSheet(BG_GREEN);
- } else if (is_aw_safe || is_execute) {
- rtc_table_->cellWidget(cnt, 1)->setStyleSheet(BG_YELLOW);
- } else {
- rtc_table_->cellWidget(cnt, 1)->setStyleSheet(BG_RED);
- }
- cnt++;
- }
- rtc_table_->update();
-}
-} // namespace rviz_plugins
-
-#include
-PLUGINLIB_EXPORT_CLASS(rviz_plugins::RTCManagerPanel, rviz_common::Panel)
diff --git a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp
deleted file mode 100644
index 8bdaef94b6254..0000000000000
--- a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp
+++ /dev/null
@@ -1,132 +0,0 @@
-//
-// Copyright 2020 Tier IV, Inc. All rights reserved.
-//
-// 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 RTC_MANAGER_PANEL_HPP_
-#define RTC_MANAGER_PANEL_HPP_
-
-#include
-#include
-#include
-#include
-#include
-
-#ifndef Q_MOC_RUN
-// cpp
-#include
-#include
-#include
-#include
-// ros
-#include
-#include
-
-#include
-// autoware
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#endif
-
-namespace rviz_plugins
-{
-using tier4_rtc_msgs::msg::Command;
-using tier4_rtc_msgs::msg::CooperateCommand;
-using tier4_rtc_msgs::msg::CooperateResponse;
-using tier4_rtc_msgs::msg::CooperateStatus;
-using tier4_rtc_msgs::msg::CooperateStatusArray;
-using tier4_rtc_msgs::msg::Module;
-using tier4_rtc_msgs::srv::AutoMode;
-using tier4_rtc_msgs::srv::CooperateCommands;
-using unique_identifier_msgs::msg::UUID;
-
-static const QString BG_BLUE = "background-color: #3dffff;";
-static const QString BG_YELLOW = "background-color: #ffff3d;";
-static const QString BG_PURPLE = "background-color: #9e3dff;";
-static const QString BG_ORANGE = "background-color: #ff7f00;";
-static const QString BG_GREEN = "background-color: #3dff3d;";
-static const QString BG_RED = "background-color: #ff3d3d;";
-
-struct RTCAutoMode : public QObject
-{
- Q_OBJECT
-
-public Q_SLOTS:
- void onChangeToAutoMode();
- void onChangeToManualMode();
-
-public:
- std::string module_name;
- QPushButton * auto_module_button_ptr;
- QPushButton * manual_module_button_ptr;
- QLabel * auto_manual_mode_label;
- rclcpp::Client::SharedPtr enable_auto_mode_cli;
-};
-
-class RTCManagerPanel : public rviz_common::Panel
-{
- Q_OBJECT
-public Q_SLOTS:
- void onClickExecution();
- void onClickWait();
- void onClickVelocityChangeRequest();
- void onClickExecutePathChange();
- void onClickWaitPathChange();
- void onClickExecuteVelChange();
- void onClickWaitVelChange();
-
-public:
- explicit RTCManagerPanel(QWidget * parent = nullptr);
- void onInitialize() override;
-
-protected:
- void onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg);
- void onEnableService(
- const AutoMode::Request::SharedPtr request, const AutoMode::Response::SharedPtr response) const;
- void onClickCommandRequest(const uint8_t command);
- void onClickChangeRequest(const bool is_path_change, const uint8_t command);
-
-private:
- rclcpp::Node::SharedPtr raw_node_;
- rclcpp::Subscription::SharedPtr sub_rtc_status_;
- rclcpp::Client::SharedPtr client_rtc_commands_;
- rclcpp::Client::SharedPtr enable_auto_mode_cli_;
- std::vector auto_modes_;
-
- std::shared_ptr cooperate_statuses_ptr_;
- QTableWidget * rtc_table_;
- QTableWidget * auto_mode_table_;
- QPushButton * path_change_button_ptr_ = {nullptr};
- QPushButton * velocity_change_button_ptr_ = {nullptr};
- QPushButton * exec_path_change_button_ptr_ = {nullptr};
- QPushButton * wait_path_change_button_ptr_ = {nullptr};
- QPushButton * exec_vel_change_button_ptr_ = {nullptr};
- QPushButton * wait_vel_change_button_ptr_ = {nullptr};
- QPushButton * exec_button_ptr_ = {nullptr};
- QPushButton * wait_button_ptr_ = {nullptr};
- QLabel * num_rtc_status_ptr_ = {nullptr};
-
- size_t column_size_ = {7};
- std::string enable_auto_mode_namespace_ = "/planning/enable_auto_mode";
-};
-
-} // namespace rviz_plugins
-
-#endif // RTC_MANAGER_PANEL_HPP_
diff --git a/common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt b/common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt
deleted file mode 100644
index cdc57743a6cb1..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt
+++ /dev/null
@@ -1,36 +0,0 @@
-cmake_minimum_required(VERSION 3.14)
-project(tier4_automatic_goal_rviz_plugin)
-
-find_package(autoware_cmake REQUIRED)
-autoware_package()
-
-find_package(Qt5 REQUIRED Core Widgets)
-set(QT_LIBRARIES Qt5::Widgets)
-set(CMAKE_AUTOMOC ON)
-set(CMAKE_INCLUDE_CURRENT_DIR ON)
-add_definitions(-DQT_NO_KEYWORDS)
-
-ament_auto_add_library(${PROJECT_NAME} SHARED
- src/automatic_checkpoint_append_tool.cpp
- src/automatic_goal_sender.cpp
- src/automatic_goal_append_tool.cpp
- src/automatic_goal_panel.cpp
-)
-
-ament_auto_add_executable(automatic_goal_sender
- src/automatic_goal_sender.cpp
-)
-
-target_link_libraries(${PROJECT_NAME}
- ${QT_LIBRARIES}
-)
-
-# Export the plugin to be imported by rviz2
-pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml)
-
-ament_auto_package(
- INSTALL_TO_SHARE
- launch
- icons
- plugins
-)
diff --git a/common/tier4_automatic_goal_rviz_plugin/README.md b/common/tier4_automatic_goal_rviz_plugin/README.md
deleted file mode 100644
index 6fd626d5a7642..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/README.md
+++ /dev/null
@@ -1,98 +0,0 @@
-# tier4_automatic_goal_rviz_plugin
-
-## Purpose
-
-1. Defining a `GoalsList` by adding goals using `RvizTool` (Pose on the map).
-
-2. Automatic execution of the created `GoalsList` from the selected goal - it can be stopped and restarted.
-
-3. Looping the current `GoalsList`.
-
-4. Saving achieved goals to a file.
-
-5. Plan the route to one (single) selected goal and starting that route - it can be stopped and restarted.
-
-6. Remove any goal from the list or clear the current route.
-
-7. Save the current `GoalsList` to a file and load the list from the file.
-
-8. The application enables/disables access to options depending on the current state.
-
-9. The saved `GoalsList` can be executed without using a plugin - using a node `automatic_goal_sender`.
-
-## Inputs / Outputs
-
-### Input
-
-| Name | Type | Description |
-| ---------------------------- | ------------------------------------------------- | ------------------------------------------------ |
-| `/api/operation_mode/state` | `autoware_adapi_v1_msgs::msg::OperationModeState` | The topic represents the state of operation mode |
-| `/api/routing/state` | `autoware_adapi_v1_msgs::msg::RouteState` | The topic represents the state of route |
-| `/rviz2/automatic_goal/goal` | `geometry_msgs::msgs::PoseStamped` | The topic for adding goals to GoalsList |
-
-### Output
-
-| Name | Type | Description |
-| ------------------------------------------ | -------------------------------------------------- | -------------------------------------------------- |
-| `/api/operation_mode/change_to_autonomous` | `autoware_adapi_v1_msgs::srv::ChangeOperationMode` | The service to change operation mode to autonomous |
-| `/api/operation_mode/change_to_stop` | `autoware_adapi_v1_msgs::srv::ChangeOperationMode` | The service to change operation mode to stop |
-| `/api/routing/set_route_points` | `autoware_adapi_v1_msgs::srv::SetRoutePoints` | The service to set route |
-| `/api/routing/clear_route` | `autoware_adapi_v1_msgs::srv::ClearRoute` | The service to clear route state |
-| `/rviz2/automatic_goal/markers` | `visualization_msgs::msg::MarkerArray` | The topic to visualize goals as rviz markers |
-
-## HowToUse
-
-1. Start rviz and select panels/Add new panel.
-
- ![select_panel](./images/select_panels.png)
-
-2. Select `tier4_automatic_goal_rviz_plugin/AutowareAutomaticGoalPanel` and press OK.
-
-3. Select Add a new tool.
-
- ![select_tool](./images/select_tool.png)
-
-4. Select `tier4_automatic_goal_rviz_plugin/AutowareAutomaticGoalTool` and press OK.
-
-5. Add goals visualization as markers to `Displays`.
-
- ![markers](./images/markers.png)
-
-6. Append goals to the `GoalsList` to be achieved using `2D Append Goal` - in such a way that routes can be planned.
-
-7. Start sequential planning and goal achievement by clicking `Send goals automatically`
-
- ![panel](./images/panel.png)
-
-8. You can save `GoalsList` by clicking `Save to file`.
-
-9. After saving, you can run the `GoalsList` without using a plugin also:
- - example: `ros2 launch tier4_automatic_goal_rviz_plugin automatic_goal_sender.launch.xml goals_list_file_path:="/tmp/goals_list.yaml" goals_achieved_dir_path:="/tmp/"`
- - `goals_list_file_path` - is the path to the saved `GoalsList` file to be loaded
- - `goals_achieved_dir_path` - is the path to the directory where the file `goals_achieved.log` will be created and the achieved goals will be written to it
-
-### Hints
-
-If the application (Engagement) goes into `ERROR` mode (usually returns to `EDITING` later), it means that one of the services returned a calling error (`code!=0`).
-In this situation, check the terminal output for more information.
-
-- Often it is enough to try again.
-- Sometimes a clearing of the current route is required before retrying.
-
-## Material Design Icons
-
-This project uses [Material Design Icons](https://developers.google.com/fonts/docs/material_symbols) by Google. These icons are used under the terms of the Apache License, Version 2.0.
-
-Material Design Icons are a collection of symbols provided by Google that are used to enhance the user interface of applications, websites, and other digital products.
-
-### License
-
-The Material Design Icons are licensed under the Apache License, Version 2.0. You may obtain a copy of the License at:
-
-
-
-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.
-
-### Acknowledgments
-
-We would like to express our gratitude to Google for making these icons available to the community, helping developers and designers enhance the visual appeal and user experience of their projects.
diff --git a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticCheckpointTool.png b/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticCheckpointTool.png
deleted file mode 100644
index 4f5b4961f2500..0000000000000
Binary files a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticCheckpointTool.png and /dev/null differ
diff --git a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalPanel.png b/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalPanel.png
deleted file mode 100644
index 6a67573717ae1..0000000000000
Binary files a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalPanel.png and /dev/null differ
diff --git a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalTool.png b/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalTool.png
deleted file mode 100644
index 58d12f95ebfd6..0000000000000
Binary files a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalTool.png and /dev/null differ
diff --git a/common/tier4_automatic_goal_rviz_plugin/images/markers.png b/common/tier4_automatic_goal_rviz_plugin/images/markers.png
deleted file mode 100644
index 8dd4d9d02bef4..0000000000000
Binary files a/common/tier4_automatic_goal_rviz_plugin/images/markers.png and /dev/null differ
diff --git a/common/tier4_automatic_goal_rviz_plugin/images/panel.png b/common/tier4_automatic_goal_rviz_plugin/images/panel.png
deleted file mode 100644
index 1800202ea9f57..0000000000000
Binary files a/common/tier4_automatic_goal_rviz_plugin/images/panel.png and /dev/null differ
diff --git a/common/tier4_automatic_goal_rviz_plugin/images/select_panels.png b/common/tier4_automatic_goal_rviz_plugin/images/select_panels.png
deleted file mode 100644
index 61dd9e1d7a1b3..0000000000000
Binary files a/common/tier4_automatic_goal_rviz_plugin/images/select_panels.png and /dev/null differ
diff --git a/common/tier4_automatic_goal_rviz_plugin/images/select_tool.png b/common/tier4_automatic_goal_rviz_plugin/images/select_tool.png
deleted file mode 100644
index a6ddc6d24c575..0000000000000
Binary files a/common/tier4_automatic_goal_rviz_plugin/images/select_tool.png and /dev/null differ
diff --git a/common/tier4_automatic_goal_rviz_plugin/launch/automatic_goal_sender.launch.xml b/common/tier4_automatic_goal_rviz_plugin/launch/automatic_goal_sender.launch.xml
deleted file mode 100644
index a9af89c078348..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/launch/automatic_goal_sender.launch.xml
+++ /dev/null
@@ -1,10 +0,0 @@
-
-
-
-
-
-
-
-
-
-
diff --git a/common/tier4_automatic_goal_rviz_plugin/package.xml b/common/tier4_automatic_goal_rviz_plugin/package.xml
deleted file mode 100644
index fb5331379acb6..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/package.xml
+++ /dev/null
@@ -1,38 +0,0 @@
-
-
-
- tier4_automatic_goal_rviz_plugin
- 0.0.0
- The autoware automatic goal rviz plugin package
- Shumpei Wakabayashi
- Dawid Moszyński
- Kyoichi Sugahara
- Satoshi Ota
- Apache License 2.0
- Dawid Moszyński
-
- ament_cmake_auto
- autoware_cmake
- autoware_adapi_v1_msgs
- geometry_msgs
- libqt5-core
- libqt5-gui
- libqt5-widgets
- qtbase5-dev
- rclcpp
- rviz_common
- rviz_default_plugins
- tf2
- tf2_geometry_msgs
- tier4_autoware_utils
- visualization_msgs
- yaml-cpp
-
- ament_lint_auto
- autoware_lint_common
-
-
- ament_cmake
-
-
-
diff --git a/common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml b/common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml
deleted file mode 100644
index e9d77491941ed..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml
+++ /dev/null
@@ -1,17 +0,0 @@
-
-
- AutowareAutomaticGoalPanel
-
-
- AutowareAutomaticGoalTool
-
-
- AutowareAutomaticCheckpointTool
-
-
diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.cpp
deleted file mode 100644
index 4efa6fedbaabd..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.cpp
+++ /dev/null
@@ -1,122 +0,0 @@
-// Copyright 2024 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.
-/*
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2012, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above
- * copyright notice, this list of conditions and the following
- * disclaimer in the documentation and/or other materials provided
- * with the distribution.
- * * Neither the name of Willow Garage, Inc. nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "automatic_checkpoint_append_tool.hpp"
-
-#ifdef ROS_DISTRO_GALACTIC
-#include
-#else
-#include
-#endif
-#include
-
-#include
-
-namespace rviz_plugins
-{
-AutowareAutomaticCheckpointTool::AutowareAutomaticCheckpointTool()
-{
- shortcut_key_ = 'c';
-
- pose_topic_property_ = new rviz_common::properties::StringProperty(
- "Pose Topic", "~/automatic_goal/checkpoint", "The topic on which to publish automatic_goal.",
- getPropertyContainer(), SLOT(updateTopic()), this);
- std_dev_x_ = new rviz_common::properties::FloatProperty(
- "X std deviation", 0.5, "X standard deviation for checkpoint pose [m]", getPropertyContainer());
- std_dev_y_ = new rviz_common::properties::FloatProperty(
- "Y std deviation", 0.5, "Y standard deviation for checkpoint pose [m]", getPropertyContainer());
- std_dev_theta_ = new rviz_common::properties::FloatProperty(
- "Theta std deviation", M_PI / 12.0, "Theta standard deviation for checkpoint pose [rad]",
- getPropertyContainer());
- position_z_ = new rviz_common::properties::FloatProperty(
- "Z position", 0.0, "Z position for checkpoint pose [m]", getPropertyContainer());
- std_dev_x_->setMin(0);
- std_dev_y_->setMin(0);
- std_dev_theta_->setMin(0);
- position_z_->setMin(0);
-}
-
-void AutowareAutomaticCheckpointTool::onInitialize()
-{
- PoseTool::onInitialize();
- setName("2D AppendCheckpoint");
- updateTopic();
-}
-
-void AutowareAutomaticCheckpointTool::updateTopic()
-{
- rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node();
- pose_pub_ = raw_node->create_publisher(
- pose_topic_property_->getStdString(), 1);
- clock_ = raw_node->get_clock();
-}
-
-void AutowareAutomaticCheckpointTool::onPoseSet(double x, double y, double theta)
-{
- // pose
- std::string fixed_frame = context_->getFixedFrame().toStdString();
- geometry_msgs::msg::PoseStamped pose;
- pose.header.frame_id = fixed_frame;
- pose.header.stamp = clock_->now();
- pose.pose.position.x = x;
- pose.pose.position.y = y;
- pose.pose.position.z = position_z_->getFloat();
-
- tf2::Quaternion quat;
- quat.setRPY(0.0, 0.0, theta);
- pose.pose.orientation = tf2::toMsg(quat);
- RCLCPP_INFO(
- rclcpp::get_logger("AutowareAutomaticCheckpointTool"),
- "Setting pose: %.3f %.3f %.3f %.3f [frame=%s]", x, y, position_z_->getFloat(), theta,
- fixed_frame.c_str());
- pose_pub_->publish(pose);
-}
-
-} // end namespace rviz_plugins
-
-#include
-PLUGINLIB_EXPORT_CLASS(rviz_plugins::AutowareAutomaticCheckpointTool, rviz_common::Tool)
diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.hpp
deleted file mode 100644
index 4ea3fa4bd009a..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.hpp
+++ /dev/null
@@ -1,91 +0,0 @@
-// Copyright 2024 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.
-/*
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2012, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above
- * copyright notice, this list of conditions and the following
- * disclaimer in the documentation and/or other materials provided
- * with the distribution.
- * * Neither the name of Willow Garage, Inc. nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef AUTOMATIC_CHECKPOINT_APPEND_TOOL_HPP_
-#define AUTOMATIC_CHECKPOINT_APPEND_TOOL_HPP_
-
-#ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
-#include
-#include
-#include
-#include
-#include
-#include
-#endif
-
-#include
-
-namespace rviz_plugins
-{
-class AutowareAutomaticCheckpointTool : public rviz_default_plugins::tools::PoseTool
-{
- Q_OBJECT
-
-public:
- AutowareAutomaticCheckpointTool();
- void onInitialize() override;
-
-protected:
- void onPoseSet(double x, double y, double theta) override;
-
-private Q_SLOTS:
- void updateTopic();
-
-private: // NOLINT for Qt
- rclcpp::Clock::SharedPtr clock_{nullptr};
- rclcpp::Publisher::SharedPtr pose_pub_{nullptr};
-
- rviz_common::properties::StringProperty * pose_topic_property_{nullptr};
- rviz_common::properties::FloatProperty * std_dev_x_{nullptr};
- rviz_common::properties::FloatProperty * std_dev_y_{nullptr};
- rviz_common::properties::FloatProperty * std_dev_theta_{nullptr};
- rviz_common::properties::FloatProperty * position_z_{nullptr};
-};
-
-} // namespace rviz_plugins
-
-#endif // AUTOMATIC_CHECKPOINT_APPEND_TOOL_HPP_
diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp
deleted file mode 100644
index 43fc0edcccf84..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp
+++ /dev/null
@@ -1,121 +0,0 @@
-// Copyright 2023 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.
-/*
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2012, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above
- * copyright notice, this list of conditions and the following
- * disclaimer in the documentation and/or other materials provided
- * with the distribution.
- * * Neither the name of Willow Garage, Inc. nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "automatic_goal_append_tool.hpp"
-
-#ifdef ROS_DISTRO_GALACTIC
-#include
-#else
-#include
-#endif
-#include
-
-#include
-
-namespace rviz_plugins
-{
-AutowareAutomaticGoalTool::AutowareAutomaticGoalTool()
-{
- shortcut_key_ = 'c';
-
- pose_topic_property_ = new rviz_common::properties::StringProperty(
- "Pose Topic", "~/automatic_goal/goal", "The topic on which to publish automatic_goal.",
- getPropertyContainer(), SLOT(updateTopic()), this);
- std_dev_x_ = new rviz_common::properties::FloatProperty(
- "X std deviation", 0.5, "X standard deviation for checkpoint pose [m]", getPropertyContainer());
- std_dev_y_ = new rviz_common::properties::FloatProperty(
- "Y std deviation", 0.5, "Y standard deviation for checkpoint pose [m]", getPropertyContainer());
- std_dev_theta_ = new rviz_common::properties::FloatProperty(
- "Theta std deviation", M_PI / 12.0, "Theta standard deviation for checkpoint pose [rad]",
- getPropertyContainer());
- position_z_ = new rviz_common::properties::FloatProperty(
- "Z position", 0.0, "Z position for checkpoint pose [m]", getPropertyContainer());
- std_dev_x_->setMin(0);
- std_dev_y_->setMin(0);
- std_dev_theta_->setMin(0);
- position_z_->setMin(0);
-}
-
-void AutowareAutomaticGoalTool::onInitialize()
-{
- PoseTool::onInitialize();
- setName("2D AppendGoal");
- updateTopic();
-}
-
-void AutowareAutomaticGoalTool::updateTopic()
-{
- rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node();
- pose_pub_ = raw_node->create_publisher(
- pose_topic_property_->getStdString(), 1);
- clock_ = raw_node->get_clock();
-}
-
-void AutowareAutomaticGoalTool::onPoseSet(double x, double y, double theta)
-{
- // pose
- std::string fixed_frame = context_->getFixedFrame().toStdString();
- geometry_msgs::msg::PoseStamped pose;
- pose.header.frame_id = fixed_frame;
- pose.header.stamp = clock_->now();
- pose.pose.position.x = x;
- pose.pose.position.y = y;
- pose.pose.position.z = position_z_->getFloat();
-
- tf2::Quaternion quat;
- quat.setRPY(0.0, 0.0, theta);
- pose.pose.orientation = tf2::toMsg(quat);
- RCLCPP_INFO(
- rclcpp::get_logger("AutowareAutomaticGoalTool"), "Setting pose: %.3f %.3f %.3f %.3f [frame=%s]",
- x, y, position_z_->getFloat(), theta, fixed_frame.c_str());
- pose_pub_->publish(pose);
-}
-
-} // end namespace rviz_plugins
-
-#include
-PLUGINLIB_EXPORT_CLASS(rviz_plugins::AutowareAutomaticGoalTool, rviz_common::Tool)
diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp
deleted file mode 100644
index 6fc98cee9afa1..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp
+++ /dev/null
@@ -1,91 +0,0 @@
-// Copyright 2023 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.
-/*
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2012, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above
- * copyright notice, this list of conditions and the following
- * disclaimer in the documentation and/or other materials provided
- * with the distribution.
- * * Neither the name of Willow Garage, Inc. nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef AUTOMATIC_GOAL_APPEND_TOOL_HPP_
-#define AUTOMATIC_GOAL_APPEND_TOOL_HPP_
-
-#ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
-#include
-#include
-#include
-#include
-#include
-#include
-#endif
-
-#include
-
-namespace rviz_plugins
-{
-class AutowareAutomaticGoalTool : public rviz_default_plugins::tools::PoseTool
-{
- Q_OBJECT
-
-public:
- AutowareAutomaticGoalTool();
- void onInitialize() override;
-
-protected:
- void onPoseSet(double x, double y, double theta) override;
-
-private Q_SLOTS:
- void updateTopic();
-
-private: // NOLINT for Qt
- rclcpp::Clock::SharedPtr clock_{nullptr};
- rclcpp::Publisher::SharedPtr pose_pub_{nullptr};
-
- rviz_common::properties::StringProperty * pose_topic_property_{nullptr};
- rviz_common::properties::FloatProperty * std_dev_x_{nullptr};
- rviz_common::properties::FloatProperty * std_dev_y_{nullptr};
- rviz_common::properties::FloatProperty * std_dev_theta_{nullptr};
- rviz_common::properties::FloatProperty * position_z_{nullptr};
-};
-
-} // namespace rviz_plugins
-
-#endif // AUTOMATIC_GOAL_APPEND_TOOL_HPP_
diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp
deleted file mode 100644
index 6b8d7765a989a..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp
+++ /dev/null
@@ -1,532 +0,0 @@
-//
-// Copyright 2023 TIER IV, Inc. All rights reserved.
-//
-// 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.
-//
-
-#include "automatic_goal_panel.hpp"
-
-#include
-
-namespace rviz_plugins
-{
-AutowareAutomaticGoalPanel::AutowareAutomaticGoalPanel(QWidget * parent)
-: rviz_common::Panel(parent)
-{
- qt_timer_ = new QTimer(this);
- connect(
- qt_timer_, &QTimer::timeout, this, &AutowareAutomaticGoalPanel::updateAutoExecutionTimerTick);
-
- auto * h_layout = new QHBoxLayout(this);
- auto * v_layout = new QVBoxLayout(this);
- h_layout->addWidget(makeGoalsListGroup());
- v_layout->addWidget(makeEngagementGroup());
- v_layout->addWidget(makeRoutingGroup());
- h_layout->addLayout(v_layout);
- setLayout(h_layout);
-}
-
-// Layouts
-QGroupBox * AutowareAutomaticGoalPanel::makeGoalsListGroup()
-{
- auto * group = new QGroupBox("GoalsList", this);
- auto * grid = new QGridLayout(group);
-
- load_file_btn_ptr_ = new QPushButton("Load from file", group);
- connect(load_file_btn_ptr_, SIGNAL(clicked()), SLOT(onClickLoadListFromFile()));
- grid->addWidget(load_file_btn_ptr_, 0, 0);
-
- save_file_btn_ptr_ = new QPushButton("Save to file", group);
- connect(save_file_btn_ptr_, SIGNAL(clicked()), SLOT(onClickSaveListToFile()));
- grid->addWidget(save_file_btn_ptr_, 1, 0);
-
- goals_list_widget_ptr_ = new QListWidget(group);
- goals_list_widget_ptr_->setStyleSheet("border:1px solid black;");
- grid->addWidget(goals_list_widget_ptr_, 2, 0);
-
- remove_selected_goal_btn_ptr_ = new QPushButton("Remove selected", group);
- connect(remove_selected_goal_btn_ptr_, SIGNAL(clicked()), SLOT(onClickRemove()));
- grid->addWidget(remove_selected_goal_btn_ptr_, 3, 0);
-
- loop_list_btn_ptr_ = new QPushButton("Loop list", group);
- loop_list_btn_ptr_->setCheckable(true);
- connect(loop_list_btn_ptr_, SIGNAL(toggled(bool)), SLOT(onToggleLoopList(bool)));
- grid->addWidget(loop_list_btn_ptr_, 4, 0);
-
- goals_achieved_btn_ptr_ = new QPushButton("Saving achieved goals to file", group);
- goals_achieved_btn_ptr_->setCheckable(true);
- connect(goals_achieved_btn_ptr_, SIGNAL(toggled(bool)), SLOT(onToggleSaveGoalsAchievement(bool)));
- grid->addWidget(goals_achieved_btn_ptr_, 5, 0);
-
- group->setLayout(grid);
- return group;
-}
-
-QGroupBox * AutowareAutomaticGoalPanel::makeRoutingGroup()
-{
- auto * group = new QGroupBox("Routing", this);
- auto * grid = new QGridLayout(group);
-
- routing_label_ptr_ = new QLabel("INIT", group);
- routing_label_ptr_->setMinimumSize(100, 25);
- routing_label_ptr_->setAlignment(Qt::AlignCenter);
- routing_label_ptr_->setStyleSheet("border:1px solid black;");
- grid->addWidget(routing_label_ptr_, 0, 0);
-
- clear_route_btn_ptr_ = new QPushButton("Clear planned route", group);
- connect(clear_route_btn_ptr_, &QPushButton::clicked, [this]() { onClickClearRoute(); });
- grid->addWidget(clear_route_btn_ptr_, 1, 0);
- group->setLayout(grid);
-
- group->setLayout(grid);
- return group;
-}
-
-QGroupBox * AutowareAutomaticGoalPanel::makeEngagementGroup()
-{
- auto * group = new QGroupBox("Engagement", this);
- auto * grid = new QGridLayout(group);
-
- engagement_label_ptr_ = new QLabel("INITIALIZING", group);
- engagement_label_ptr_->setMinimumSize(100, 25);
- engagement_label_ptr_->setAlignment(Qt::AlignCenter);
- engagement_label_ptr_->setStyleSheet("border:1px solid black;");
- grid->addWidget(engagement_label_ptr_, 0, 0);
-
- automatic_mode_btn_ptr_ = new QPushButton("Send goals automatically", group);
- automatic_mode_btn_ptr_->setCheckable(true);
-
- connect(automatic_mode_btn_ptr_, SIGNAL(toggled(bool)), SLOT(onToggleAutoMode(bool)));
- grid->addWidget(automatic_mode_btn_ptr_, 1, 0);
-
- plan_btn_ptr_ = new QPushButton("Plan to selected goal", group);
- connect(plan_btn_ptr_, &QPushButton::clicked, [this] { onClickPlan(); });
- grid->addWidget(plan_btn_ptr_, 2, 0);
-
- start_btn_ptr_ = new QPushButton("Start current plan", group);
- connect(start_btn_ptr_, &QPushButton::clicked, [this] { onClickStart(); });
- grid->addWidget(start_btn_ptr_, 3, 0);
-
- stop_btn_ptr_ = new QPushButton("Stop current plan", group);
- connect(stop_btn_ptr_, SIGNAL(clicked()), SLOT(onClickStop()));
- grid->addWidget(stop_btn_ptr_, 4, 0);
- group->setLayout(grid);
-
- group->setLayout(grid);
- return group;
-}
-
-void AutowareAutomaticGoalPanel::showMessageBox(const QString & string)
-{
- QMessageBox msg_box(this);
- msg_box.setText(string);
- msg_box.exec();
-}
-
-// Slots
-void AutowareAutomaticGoalPanel::onInitialize()
-{
- raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();
- pub_marker_ = raw_node_->create_publisher("~/automatic_goal/markers", 0);
- sub_append_goal_ = raw_node_->create_subscription(
- "~/automatic_goal/goal", 5,
- std::bind(&AutowareAutomaticGoalPanel::onAppendGoal, this, std::placeholders::_1));
- sub_append_checkpoint_ = raw_node_->create_subscription(
- "~/automatic_goal/checkpoint", 5,
- std::bind(&AutowareAutomaticGoalPanel::onAppendCheckpoint, this, std::placeholders::_1));
- initCommunication(raw_node_.get());
-}
-
-void AutowareAutomaticGoalPanel::onToggleLoopList(bool checked)
-{
- is_loop_list_on_ = checked;
- updateGUI();
-}
-
-void AutowareAutomaticGoalPanel::onToggleSaveGoalsAchievement(bool checked)
-{
- if (checked) {
- QString file_name = QFileDialog::getSaveFileName(
- this, tr("Save File with GoalsList"), "/tmp/goals_achieved.log",
- tr("Achieved goals (*.log)"));
- goals_achieved_file_path_ = file_name.toStdString();
- } else {
- goals_achieved_file_path_ = "";
- }
- updateGUI();
-}
-
-void AutowareAutomaticGoalPanel::onToggleAutoMode(bool checked)
-{
- if (checked && goals_list_widget_ptr_->selectedItems().count() != 1) {
- showMessageBox("Select the first goal in GoalsList");
- automatic_mode_btn_ptr_->setChecked(false);
- } else {
- if (checked) current_goal_ = goals_list_widget_ptr_->currentRow();
- is_automatic_mode_on_ = checked;
- is_automatic_mode_on_ ? qt_timer_->start(1000) : qt_timer_->stop();
- onClickClearRoute(); // here will be set State::AUTO_NEXT or State::EDITING;
- }
-}
-
-void AutowareAutomaticGoalPanel::onClickPlan()
-{
- if (goals_list_widget_ptr_->selectedItems().count() != 1) {
- showMessageBox("Select a goal in GoalsList");
- return;
- }
-
- if (callPlanToGoalIndex(cli_set_route_, goals_list_widget_ptr_->currentRow())) {
- state_ = State::PLANNING;
- updateGUI();
- }
-}
-
-void AutowareAutomaticGoalPanel::onClickStart()
-{
- if (callService(cli_change_to_autonomous_)) {
- state_ = State::STARTING;
- updateGUI();
- }
-}
-
-void AutowareAutomaticGoalPanel::onClickStop()
-{
- // if ERROR is set then the ego is already stopped
- if (state_ == State::ERROR) {
- state_ = State::STOPPED;
- updateGUI();
- } else if (callService(cli_change_to_stop_)) {
- state_ = State::STOPPING;
- updateGUI();
- }
-}
-
-void AutowareAutomaticGoalPanel::onClickClearRoute()
-{
- if (callService(cli_clear_route_)) {
- state_ = State::CLEARING;
- updateGUI();
- }
-}
-
-void AutowareAutomaticGoalPanel::onClickRemove()
-{
- if (static_cast(goals_list_widget_ptr_->currentRow()) < goals_list_.size())
- goals_list_.erase(goals_list_.begin() + goals_list_widget_ptr_->currentRow());
- resetAchievedGoals();
- updateGUI();
- updateGoalsList();
-}
-
-void AutowareAutomaticGoalPanel::onClickLoadListFromFile()
-{
- QString file_name = QFileDialog::getOpenFileName(
- this, tr("Open File with GoalsList"), "/tmp", tr("Goal lists (*.yaml)"));
- if (file_name.count() > 0) loadGoalsList(file_name.toStdString());
-}
-
-void AutowareAutomaticGoalPanel::onClickSaveListToFile()
-{
- if (!goals_list_.empty()) {
- QString file_name = QFileDialog::getSaveFileName(
- this, tr("Save File with GoalsList"), "/tmp/goals_list.yaml", tr("Goal lists (*.yaml)"));
- if (file_name.count() > 0) saveGoalsList(file_name.toStdString());
- }
-}
-
-// Inputs
-void AutowareAutomaticGoalPanel::onAppendGoal(const PoseStamped::ConstSharedPtr pose)
-{
- if (state_ == State::EDITING) {
- goals_list_.emplace_back(pose);
- updateGoalsList();
- updateGUI();
- }
-}
-
-void AutowareAutomaticGoalPanel::onAppendCheckpoint(const PoseStamped::ConstSharedPtr pose)
-{
- if (goals_list_widget_ptr_->selectedItems().count() != 1) {
- showMessageBox("Select a goal in GoalsList before set checkpoint");
- return;
- }
-
- current_goal_ = goals_list_widget_ptr_->currentRow();
- if (current_goal_ >= goals_list_.size()) {
- return;
- }
-
- goals_list_.at(current_goal_).checkpoint_pose_ptrs.push_back(pose);
- publishMarkers();
-}
-
-// Override
-void AutowareAutomaticGoalPanel::onCallResult()
-{
- updateGUI();
-}
-void AutowareAutomaticGoalPanel::onGoalListUpdated()
-{
- goals_list_widget_ptr_->clear();
- for (auto const & goal : goals_achieved_) {
- auto * item =
- new QListWidgetItem(QString::fromStdString(goal.second.first), goals_list_widget_ptr_);
- goals_list_widget_ptr_->addItem(item);
- updateGoalIcon(goals_list_widget_ptr_->count() - 1, QColor("lightGray"));
- }
- publishMarkers();
-}
-void AutowareAutomaticGoalPanel::onOperationModeUpdated(const OperationModeState::ConstSharedPtr)
-{
- updateGUI();
-}
-void AutowareAutomaticGoalPanel::onRouteUpdated(const RouteState::ConstSharedPtr msg)
-{
- std::pair style;
- if (msg->state == RouteState::UNSET)
- style = std::make_pair("UNSET", "background-color: #FFFF00;"); // yellow
- else if (msg->state == RouteState::SET)
- style = std::make_pair("SET", "background-color: #00FF00;"); // green
- else if (msg->state == RouteState::ARRIVED)
- style = std::make_pair("ARRIVED", "background-color: #FFA500;"); // orange
- else if (msg->state == RouteState::CHANGING)
- style = std::make_pair("CHANGING", "background-color: #FFFF00;"); // yellow
- else
- style = std::make_pair("UNKNOWN", "background-color: #FF0000;"); // red
-
- updateLabel(routing_label_ptr_, style.first, style.second);
- updateGUI();
-}
-
-void AutowareAutomaticGoalPanel::updateAutoExecutionTimerTick()
-{
- if (is_automatic_mode_on_) {
- if (state_ == State::AUTO_NEXT) {
- // end if loop is off
- if (current_goal_ >= goals_list_.size() && !is_loop_list_on_) {
- disableAutomaticMode();
- return;
- }
- // plan to next goal
- current_goal_ = current_goal_ % goals_list_.size();
- if (callPlanToGoalIndex(cli_set_route_, current_goal_)) {
- state_ = State::PLANNING;
- updateGUI();
- }
- } else if (state_ == State::PLANNED) {
- updateGoalIcon(current_goal_, QColor("yellow"));
- onClickStart();
- } else if (state_ == State::ARRIVED) {
- goals_achieved_[current_goal_].second++;
- updateAchievedGoalsFile(current_goal_);
- updateGoalIcon(current_goal_++, QColor("green"));
- onClickClearRoute(); // will be set AUTO_NEXT as next state_
- } else if (state_ == State::STOPPED || state_ == State::ERROR) {
- disableAutomaticMode();
- }
- }
-}
-
-// Visual updates
-void AutowareAutomaticGoalPanel::updateGUI()
-{
- deactivateButton(automatic_mode_btn_ptr_);
- deactivateButton(remove_selected_goal_btn_ptr_);
- deactivateButton(clear_route_btn_ptr_);
- deactivateButton(plan_btn_ptr_);
- deactivateButton(start_btn_ptr_);
- deactivateButton(stop_btn_ptr_);
- deactivateButton(load_file_btn_ptr_);
- deactivateButton(save_file_btn_ptr_);
- deactivateButton(loop_list_btn_ptr_);
- deactivateButton(goals_achieved_btn_ptr_);
-
- std::pair style;
- switch (state_) {
- case State::EDITING:
- activateButton(load_file_btn_ptr_);
- if (!goals_list_.empty()) {
- activateButton(goals_achieved_btn_ptr_);
- activateButton(plan_btn_ptr_);
- activateButton(remove_selected_goal_btn_ptr_);
- activateButton(automatic_mode_btn_ptr_);
- activateButton(save_file_btn_ptr_);
- activateButton(loop_list_btn_ptr_);
- }
- style = std::make_pair("EDITING", "background-color: #FFFF00;");
- break;
- case State::PLANNED:
- activateButton(start_btn_ptr_);
- activateButton(clear_route_btn_ptr_);
- activateButton(save_file_btn_ptr_);
- style = std::make_pair("PLANNED", "background-color: #00FF00;");
- break;
- case State::STARTED:
- activateButton(stop_btn_ptr_);
- activateButton(save_file_btn_ptr_);
- style = std::make_pair("STARTED", "background-color: #00FF00;");
- break;
- case State::STOPPED:
- activateButton(start_btn_ptr_);
- activateButton(automatic_mode_btn_ptr_);
- activateButton(clear_route_btn_ptr_);
- activateButton(save_file_btn_ptr_);
- style = std::make_pair("STOPPED", "background-color: #00FF00;");
- break;
- case State::ARRIVED:
- if (!is_automatic_mode_on_) onClickClearRoute(); // will be set EDITING as next state_
- break;
- case State::CLEARED:
- is_automatic_mode_on_ ? state_ = State::AUTO_NEXT : state_ = State::EDITING;
- updateGUI();
- break;
- case State::ERROR:
- activateButton(stop_btn_ptr_);
- if (!goals_list_.empty()) activateButton(save_file_btn_ptr_);
- style = std::make_pair("ERROR", "background-color: #FF0000;");
- break;
- case State::PLANNING:
- activateButton(clear_route_btn_ptr_);
- style = std::make_pair("PLANNING", "background-color: #FFA500;");
- break;
- case State::STARTING:
- style = std::make_pair("STARTING", "background-color: #FFA500;");
- break;
- case State::STOPPING:
- style = std::make_pair("STOPPING", "background-color: #FFA500;");
- break;
- case State::CLEARING:
- style = std::make_pair("CLEARING", "background-color: #FFA500;");
- break;
- default:
- break;
- }
-
- automatic_mode_btn_ptr_->setStyleSheet("");
- loop_list_btn_ptr_->setStyleSheet("");
- goals_achieved_btn_ptr_->setStyleSheet("");
- if (is_automatic_mode_on_) automatic_mode_btn_ptr_->setStyleSheet("background-color: green");
- if (is_loop_list_on_) loop_list_btn_ptr_->setStyleSheet("background-color: green");
- if (!goals_achieved_file_path_.empty())
- goals_achieved_btn_ptr_->setStyleSheet("background-color: green");
-
- updateLabel(engagement_label_ptr_, style.first, style.second);
-}
-
-void AutowareAutomaticGoalPanel::updateGoalIcon(const unsigned goal_index, const QColor & color)
-{
- QPixmap pixmap(24, 24);
- pixmap.fill(color);
- QPainter painter(&pixmap);
- painter.setPen(QColor("black"));
- painter.setFont(QFont("fixed-width", 10));
- QString text = QString::number(goals_achieved_[goal_index].second);
- painter.drawText(QRect(0, 0, 24, 24), Qt::AlignCenter, text);
- QIcon icon(pixmap);
- goals_list_widget_ptr_->item(static_cast(goal_index))->setIcon(icon);
-}
-
-void AutowareAutomaticGoalPanel::publishMarkers()
-{
- using tier4_autoware_utils::createDefaultMarker;
- using tier4_autoware_utils::createMarkerColor;
- using tier4_autoware_utils::createMarkerScale;
-
- MarkerArray text_array;
- MarkerArray arrow_array;
- // Clear existing
- {
- auto marker = createDefaultMarker(
- "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "names", 0L, Marker::CUBE,
- createMarkerScale(1.0, 1.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999));
- marker.action = visualization_msgs::msg::Marker::DELETEALL;
- text_array.markers.push_back(marker);
- pub_marker_->publish(text_array);
- }
-
- {
- auto marker = createDefaultMarker(
- "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "poses", 0L, Marker::CUBE,
- createMarkerScale(1.0, 1.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999));
- arrow_array.markers.push_back(marker);
- pub_marker_->publish(arrow_array);
- }
-
- text_array.markers.clear();
- arrow_array.markers.clear();
-
- const auto push_arrow_marker = [&](const auto & pose, const auto & color, const size_t id) {
- auto marker = createDefaultMarker(
- "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "poses", id, Marker::ARROW,
- createMarkerScale(1.6, 0.5, 0.5), color);
- marker.action = visualization_msgs::msg::Marker::ADD;
- marker.pose = pose;
- marker.lifetime = rclcpp::Duration(0, 0);
- marker.frame_locked = false;
- arrow_array.markers.push_back(marker);
- };
-
- const auto push_text_marker = [&](const auto & pose, const auto & text, const size_t id) {
- auto marker = createDefaultMarker(
- "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "names", id, Marker::TEXT_VIEW_FACING,
- createMarkerScale(1.6, 1.6, 1.6), createMarkerColor(1.0, 1.0, 1.0, 0.999));
- marker.action = visualization_msgs::msg::Marker::ADD;
- marker.pose = pose;
- marker.lifetime = rclcpp::Duration(0, 0);
- marker.frame_locked = false;
- marker.text = text;
- text_array.markers.push_back(marker);
- };
-
- // Publish current
- size_t id = 0;
- for (size_t i = 0; i < goals_list_.size(); ++i) {
- {
- const auto pose = goals_list_.at(i).goal_pose_ptr->pose;
- push_arrow_marker(pose, createMarkerColor(0.0, 1.0, 0.0, 0.999), id++);
- push_text_marker(pose, "Goal:" + std::to_string(i), id++);
- }
-
- for (size_t j = 0; j < goals_list_.at(i).checkpoint_pose_ptrs.size(); ++j) {
- const auto pose = goals_list_.at(i).checkpoint_pose_ptrs.at(j)->pose;
- push_arrow_marker(pose, createMarkerColor(1.0, 1.0, 0.0, 0.999), id++);
- push_text_marker(
- pose, "Checkpoint:" + std::to_string(i) + "[Goal:" + std::to_string(j) + "]", id++);
- }
- }
- pub_marker_->publish(text_array);
- pub_marker_->publish(arrow_array);
-}
-
-// File
-void AutowareAutomaticGoalPanel::saveGoalsList(const std::string & file_path)
-{
- YAML::Node node;
- for (unsigned i = 0; i < goals_list_.size(); ++i) {
- node[i]["position_x"] = goals_list_[i].goal_pose_ptr->pose.position.x;
- node[i]["position_y"] = goals_list_[i].goal_pose_ptr->pose.position.y;
- node[i]["position_z"] = goals_list_[i].goal_pose_ptr->pose.position.z;
- node[i]["orientation_x"] = goals_list_[i].goal_pose_ptr->pose.orientation.x;
- node[i]["orientation_y"] = goals_list_[i].goal_pose_ptr->pose.orientation.y;
- node[i]["orientation_z"] = goals_list_[i].goal_pose_ptr->pose.orientation.z;
- node[i]["orientation_w"] = goals_list_[i].goal_pose_ptr->pose.orientation.w;
- }
- std::ofstream file_out(file_path);
- file_out << node;
- file_out.close();
-}
-
-} // namespace rviz_plugins
-#include
-PLUGINLIB_EXPORT_CLASS(rviz_plugins::AutowareAutomaticGoalPanel, rviz_common::Panel)
diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp
deleted file mode 100644
index 72a5bd4fb80fe..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp
+++ /dev/null
@@ -1,151 +0,0 @@
-//
-// Copyright 2023 TIER IV, Inc. All rights reserved.
-//
-// 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 AUTOMATIC_GOAL_PANEL_HPP_
-#define AUTOMATIC_GOAL_PANEL_HPP_
-
-#include "automatic_goal_sender.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
-
-namespace rviz_plugins
-{
-class AutowareAutomaticGoalPanel : public rviz_common::Panel,
- public automatic_goal::AutowareAutomaticGoalSender
-{
- using State = automatic_goal::AutomaticGoalState;
- using Pose = geometry_msgs::msg::Pose;
- using PoseStamped = geometry_msgs::msg::PoseStamped;
- using Marker = visualization_msgs::msg::Marker;
- using MarkerArray = visualization_msgs::msg::MarkerArray;
- using OperationModeState = autoware_adapi_v1_msgs::msg::OperationModeState;
- using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
- using RouteState = autoware_adapi_v1_msgs::msg::RouteState;
- using SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints;
- using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute;
- Q_OBJECT
-
-public:
- explicit AutowareAutomaticGoalPanel(QWidget * parent = nullptr);
- void onInitialize() override;
-
-public Q_SLOTS: // NOLINT for Qt
- void onToggleLoopList(bool checked);
- void onToggleAutoMode(bool checked);
- void onToggleSaveGoalsAchievement(bool checked);
- void onClickPlan();
- void onClickStart();
- void onClickStop();
- void onClickClearRoute();
- void onClickRemove();
- void onClickLoadListFromFile();
- void onClickSaveListToFile();
-
-private:
- // Override
- void updateAutoExecutionTimerTick() override;
- void onRouteUpdated(const RouteState::ConstSharedPtr msg) override;
- void onOperationModeUpdated(const OperationModeState::ConstSharedPtr msg) override;
- void onCallResult() override;
- void onGoalListUpdated() override;
-
- // Inputs
- void onAppendGoal(const PoseStamped::ConstSharedPtr pose);
- void onAppendCheckpoint(const PoseStamped::ConstSharedPtr pose);
-
- // Visual updates
- void updateGUI();
- void updateGoalIcon(const unsigned goal_index, const QColor & color);
- void publishMarkers();
- void showMessageBox(const QString & string);
- void disableAutomaticMode() { automatic_mode_btn_ptr_->setChecked(false); }
- static void activateButton(QAbstractButton * btn) { btn->setEnabled(true); }
- static void deactivateButton(QAbstractButton * btn) { btn->setEnabled(false); }
- static void updateLabel(QLabel * label, const QString & text, const QString & style_sheet)
- {
- label->setText(text);
- label->setStyleSheet(style_sheet);
- }
- // File
- void saveGoalsList(const std::string & file);
-
- // Pub/Sub
- rclcpp::Publisher::SharedPtr pub_marker_{nullptr};
- rclcpp::Subscription::SharedPtr sub_append_goal_{nullptr};
- rclcpp::Subscription::SharedPtr sub_append_checkpoint_{nullptr};
-
- // Containers
- rclcpp::Node::SharedPtr raw_node_{nullptr};
- bool is_automatic_mode_on_{false};
- bool is_loop_list_on_{false};
-
- // QT Containers
- QGroupBox * makeGoalsListGroup();
- QGroupBox * makeRoutingGroup();
- QGroupBox * makeEngagementGroup();
- QTimer * qt_timer_{nullptr};
- QListWidget * goals_list_widget_ptr_{nullptr};
- QLabel * routing_label_ptr_{nullptr};
- QLabel * operation_mode_label_ptr_{nullptr};
- QLabel * engagement_label_ptr_{nullptr};
- QPushButton * loop_list_btn_ptr_{nullptr};
- QPushButton * goals_achieved_btn_ptr_{nullptr};
- QPushButton * load_file_btn_ptr_{nullptr};
- QPushButton * save_file_btn_ptr_{nullptr};
- QPushButton * automatic_mode_btn_ptr_{nullptr};
- QPushButton * remove_selected_goal_btn_ptr_{nullptr};
- QPushButton * clear_route_btn_ptr_{nullptr};
- QPushButton * plan_btn_ptr_{nullptr};
- QPushButton * start_btn_ptr_{nullptr};
- QPushButton * stop_btn_ptr_{nullptr};
-};
-} // namespace rviz_plugins
-
-#endif // AUTOMATIC_GOAL_PANEL_HPP_
diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp
deleted file mode 100644
index 3ca368a3bd1a4..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp
+++ /dev/null
@@ -1,227 +0,0 @@
-// Copyright 2016 Open Source Robotics Foundation, 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.
-#include "automatic_goal_sender.hpp"
-
-namespace automatic_goal
-{
-AutowareAutomaticGoalSender::AutowareAutomaticGoalSender() : Node("automatic_goal_sender")
-{
-}
-
-void AutowareAutomaticGoalSender::init()
-{
- loadParams(this);
- initCommunication(this);
- loadGoalsList(goals_list_file_path_);
- timer_ = this->create_wall_timer(
- std::chrono::milliseconds(500),
- std::bind(&AutowareAutomaticGoalSender::updateAutoExecutionTimerTick, this));
-
- // Print info
- RCLCPP_INFO_STREAM(get_logger(), "GoalsList has been loaded from: " << goals_list_file_path_);
- for (auto const & goal : goals_achieved_)
- RCLCPP_INFO_STREAM(get_logger(), "Loaded: " << goal.second.first);
- RCLCPP_INFO_STREAM(
- get_logger(), "Achieved goals will be saved in: " << goals_achieved_file_path_);
-}
-
-void AutowareAutomaticGoalSender::loadParams(rclcpp::Node * node)
-{
- namespace fs = std::filesystem;
- node->declare_parameter("goals_list_file_path", "");
- node->declare_parameter("goals_achieved_dir_path", "");
- // goals_list
- goals_list_file_path_ = node->get_parameter("goals_list_file_path").as_string();
- if (!fs::exists(goals_list_file_path_) || !fs::is_regular_file(goals_list_file_path_))
- throw std::invalid_argument(
- "goals_list_file_path parameter - file path is invalid: " + goals_list_file_path_);
- // goals_achieved
- goals_achieved_file_path_ = node->get_parameter("goals_achieved_dir_path").as_string();
- if (!fs::exists(goals_achieved_file_path_) || fs::is_regular_file(goals_achieved_file_path_))
- throw std::invalid_argument(
- "goals_achieved_dir_path - directory path is invalid: " + goals_achieved_file_path_);
- goals_achieved_file_path_ += "goals_achieved.log";
-}
-
-void AutowareAutomaticGoalSender::initCommunication(rclcpp::Node * node)
-{
- // Executing
- sub_operation_mode_ = node->create_subscription(
- "/api/operation_mode/state", rclcpp::QoS{1}.transient_local(),
- std::bind(&AutowareAutomaticGoalSender::onOperationMode, this, std::placeholders::_1));
-
- cli_change_to_autonomous_ =
- node->create_client("/api/operation_mode/change_to_autonomous");
-
- cli_change_to_stop_ =
- node->create_client("/api/operation_mode/change_to_stop");
-
- // Planning
- sub_route_ = node->create_subscription(
- "/api/routing/state", rclcpp::QoS{1}.transient_local(),
- std::bind(&AutowareAutomaticGoalSender::onRoute, this, std::placeholders::_1));
-
- cli_clear_route_ = node->create_client("/api/routing/clear_route");
-
- cli_set_route_ = node->create_client("/api/routing/set_route_points");
-}
-
-// Sub
-void AutowareAutomaticGoalSender::onRoute(const RouteState::ConstSharedPtr msg)
-{
- if (msg->state == RouteState::UNSET && state_ == State::CLEARING)
- state_ = State::CLEARED;
- else if (msg->state == RouteState::SET && state_ == State::PLANNING)
- state_ = State::PLANNED;
- else if (msg->state == RouteState::ARRIVED && state_ == State::STARTED)
- state_ = State::ARRIVED;
- onRouteUpdated(msg);
-}
-
-void AutowareAutomaticGoalSender::onOperationMode(const OperationModeState::ConstSharedPtr msg)
-{
- if (msg->mode == OperationModeState::STOP && state_ == State::INITIALIZING)
- state_ = State::EDITING;
- else if (msg->mode == OperationModeState::STOP && state_ == State::STOPPING)
- state_ = State::STOPPED;
- else if (msg->mode == OperationModeState::AUTONOMOUS && state_ == State::STARTING)
- state_ = State::STARTED;
- onOperationModeUpdated(msg);
-}
-
-// Update
-void AutowareAutomaticGoalSender::updateGoalsList()
-{
- unsigned i = 0;
- for (const auto & goal : goals_list_) {
- std::stringstream ss;
- ss << std::fixed << std::setprecision(2);
- tf2::Quaternion tf2_quat;
- tf2::convert(goal.goal_pose_ptr->pose.orientation, tf2_quat);
- ss << "G" << i << " (" << goal.goal_pose_ptr->pose.position.x << ", ";
- ss << goal.goal_pose_ptr->pose.position.y << ", " << tf2::getYaw(tf2_quat) << ")";
- goals_achieved_.insert({i++, std::make_pair(ss.str(), 0)});
- }
- onGoalListUpdated();
-}
-
-void AutowareAutomaticGoalSender::updateAutoExecutionTimerTick()
-{
- auto goal = goals_achieved_[current_goal_].first;
-
- if (state_ == State::INITIALIZING) {
- RCLCPP_INFO_THROTTLE(
- get_logger(), *get_clock(), 3000, "Initializing... waiting for OperationModeState::STOP");
-
- } else if (state_ == State::EDITING) { // skip the editing step by default
- state_ = State::AUTO_NEXT;
-
- } else if (state_ == State::AUTO_NEXT) { // plan to next goal
- RCLCPP_INFO_STREAM(get_logger(), goal << ": Goal set as the next. Planning in progress...");
- if (callPlanToGoalIndex(cli_set_route_, current_goal_)) state_ = State::PLANNING;
-
- } else if (state_ == State::PLANNED) { // start plan to next goal
- RCLCPP_INFO_STREAM(get_logger(), goal << ": Route has been planned. Route starting...");
- if (callService(cli_change_to_autonomous_)) state_ = State::STARTING;
-
- } else if (state_ == State::STARTED) {
- RCLCPP_INFO_STREAM_THROTTLE(get_logger(), *get_clock(), 5000, goal << ": Driving to the goal.");
-
- } else if (state_ == State::ARRIVED) { // clear plan after achieving next goal, goal++
- RCLCPP_INFO_STREAM(
- get_logger(), goal << ": Goal has been ACHIEVED " << ++goals_achieved_[current_goal_].second
- << " times. Route clearing...");
- updateAchievedGoalsFile(current_goal_);
- if (callService(cli_clear_route_)) state_ = State::CLEARING;
-
- } else if (state_ == State::CLEARED) {
- RCLCPP_INFO_STREAM(get_logger(), goal << ": Route has been cleared.");
- current_goal_++;
- current_goal_ = current_goal_ % goals_list_.size();
- state_ = State::AUTO_NEXT;
-
- } else if (state_ == State::STOPPED) {
- RCLCPP_WARN_STREAM(
- get_logger(), goal << ": The execution has been stopped unexpectedly! Restarting...");
- if (callService(cli_change_to_autonomous_)) state_ = State::STARTING;
-
- } else if (state_ == State::ERROR) {
- timer_->cancel();
- throw std::runtime_error(goal + ": Error encountered during execution!");
- }
-}
-
-// File
-void AutowareAutomaticGoalSender::loadGoalsList(const std::string & file_path)
-{
- YAML::Node node = YAML::LoadFile(file_path);
- goals_list_.clear();
- for (auto && goal : node) {
- std::shared_ptr pose = std::make_shared();
- pose->header.frame_id = "map";
- pose->header.stamp = rclcpp::Time();
- pose->pose.position.x = goal["position_x"].as();
- pose->pose.position.y = goal["position_y"].as();
- pose->pose.position.z = goal["position_z"].as();
- pose->pose.orientation.x = goal["orientation_x"].as();
- pose->pose.orientation.y = goal["orientation_y"].as();
- pose->pose.orientation.z = goal["orientation_z"].as();
- pose->pose.orientation.w = goal["orientation_w"].as();
- goals_list_.emplace_back(pose);
- }
- resetAchievedGoals();
- updateGoalsList();
-}
-
-void AutowareAutomaticGoalSender::updateAchievedGoalsFile(const unsigned goal_index)
-{
- if (!goals_achieved_file_path_.empty()) {
- std::ofstream out(goals_achieved_file_path_, std::fstream::app);
- std::stringstream ss;
- ss << "[" << getTimestamp() << "] Achieved: " << goals_achieved_[goal_index].first;
- ss << ", Current number of achievements: " << goals_achieved_[goal_index].second << "\n";
- out << ss.str();
- out.close();
- }
-}
-
-void AutowareAutomaticGoalSender::resetAchievedGoals()
-{
- goals_achieved_.clear();
- if (!goals_achieved_file_path_.empty()) {
- std::ofstream out(goals_achieved_file_path_, std::fstream::app);
- out << "[" << getTimestamp()
- << "] GoalsList was loaded from a file or a goal was removed - counters have been reset\n";
- out.close();
- }
-}
-} // namespace automatic_goal
-
-int main(int argc, char * argv[])
-{
- rclcpp::init(argc, argv);
-
- std::shared_ptr node{nullptr};
- try {
- node = std::make_shared();
- node->init();
- } catch (const std::exception & e) {
- fprintf(stderr, "%s Exiting...\n", e.what());
- return 1;
- }
-
- rclcpp::spin(node);
- rclcpp::shutdown();
- return 0;
-}
diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp
deleted file mode 100644
index 88b7b5e7dac20..0000000000000
--- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp
+++ /dev/null
@@ -1,184 +0,0 @@
-// Copyright 2016 Open Source Robotics Foundation, 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 AUTOMATIC_GOAL_SENDER_HPP_
-#define AUTOMATIC_GOAL_SENDER_HPP_
-#include
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-#include
-#include
-#include