diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index eb9aca8a208d6..ddbf26ebc485c 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -194,7 +194,7 @@ planning/objects_of_interest_marker_interface/** fumiya.watanabe@tier4.jp kosuke planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp 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/autoware_path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp planning/planning_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@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 diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 0b82057144f0e..34e8c9d31d837 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -28,7 +28,7 @@ - + diff --git a/planning/.pages b/planning/.pages index be6bf0af9b2a9..a16f2a13628a1 100644 --- a/planning/.pages +++ b/planning/.pages @@ -53,8 +53,8 @@ nav: - 'Obstacle Stop Planner': planning/obstacle_stop_planner - 'Obstacle Velocity Limiter': planning/obstacle_velocity_limiter - 'Path Smoother': - - 'About Path Smoother': planning/path_smoother - - 'Elastic Band': planning/path_smoother/docs/eb + - 'About Path Smoother': planning/autoware_path_smoother + - 'Elastic Band': planning/autoware_path_smoother/docs/eb - 'Sampling Based Planner': - 'Path Sample': planning/sampling_based_planner/autoware_path_sampler - 'Common library': planning/sampling_based_planner/autoware_sampler_common diff --git a/planning/path_smoother/CMakeLists.txt b/planning/autoware_path_smoother/CMakeLists.txt similarity index 70% rename from planning/path_smoother/CMakeLists.txt rename to planning/autoware_path_smoother/CMakeLists.txt index b2f42181f9a0f..a5873fe3735ef 100644 --- a/planning/path_smoother/CMakeLists.txt +++ b/planning/autoware_path_smoother/CMakeLists.txt @@ -1,23 +1,23 @@ cmake_minimum_required(VERSION 3.14) -project(path_smoother) +project(autoware_path_smoother) find_package(autoware_cmake REQUIRED) autoware_package() find_package(Eigen3 REQUIRED) -ament_auto_add_library(path_smoother SHARED +ament_auto_add_library(autoware_path_smoother SHARED DIRECTORY src ) -target_include_directories(path_smoother +target_include_directories(autoware_path_smoother SYSTEM PUBLIC ${EIGEN3_INCLUDE_DIR} ) # register node -rclcpp_components_register_node(path_smoother - PLUGIN "path_smoother::ElasticBandSmoother" +rclcpp_components_register_node(autoware_path_smoother + PLUGIN "autoware::path_smoother::ElasticBandSmoother" EXECUTABLE elastic_band_smoother ) diff --git a/planning/path_smoother/README.md b/planning/autoware_path_smoother/README.md similarity index 100% rename from planning/path_smoother/README.md rename to planning/autoware_path_smoother/README.md diff --git a/planning/path_smoother/config/elastic_band_smoother.param.yaml b/planning/autoware_path_smoother/config/elastic_band_smoother.param.yaml similarity index 100% rename from planning/path_smoother/config/elastic_band_smoother.param.yaml rename to planning/autoware_path_smoother/config/elastic_band_smoother.param.yaml diff --git a/planning/path_smoother/docs/eb.md b/planning/autoware_path_smoother/docs/eb.md similarity index 100% rename from planning/path_smoother/docs/eb.md rename to planning/autoware_path_smoother/docs/eb.md diff --git a/planning/path_smoother/include/path_smoother/common_structs.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/common_structs.hpp similarity index 92% rename from planning/path_smoother/include/path_smoother/common_structs.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/common_structs.hpp index d44c964cf634c..18f5ef82fd6d4 100644 --- a/planning/path_smoother/include/path_smoother/common_structs.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/common_structs.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__COMMON_STRUCTS_HPP_ -#define PATH_SMOOTHER__COMMON_STRUCTS_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__COMMON_STRUCTS_HPP_ +#define AUTOWARE_PATH_SMOOTHER__COMMON_STRUCTS_HPP_ -#include "path_smoother/type_alias.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" @@ -25,7 +25,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { struct Bounds; @@ -131,6 +131,6 @@ struct EgoNearestParam double dist_threshold{0.0}; double yaw_threshold{0.0}; }; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__COMMON_STRUCTS_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__COMMON_STRUCTS_HPP_ diff --git a/planning/path_smoother/include/path_smoother/elastic_band.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band.hpp similarity index 91% rename from planning/path_smoother/include/path_smoother/elastic_band.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band.hpp index 1915757b360a4..65b9db9098561 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__ELASTIC_BAND_HPP_ -#define PATH_SMOOTHER__ELASTIC_BAND_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_HPP_ +#define AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_HPP_ +#include "autoware_path_smoother/common_structs.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include "osqp_interface/osqp_interface.hpp" -#include "path_smoother/common_structs.hpp" -#include "path_smoother/type_alias.hpp" #include @@ -27,7 +27,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { class EBPathSmoother { @@ -128,6 +128,6 @@ class EBPathSmoother const std::vector & optimized_points, const std::vector & traj_points, const int pad_start_idx) const; }; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__ELASTIC_BAND_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_HPP_ diff --git a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band_smoother.hpp similarity index 89% rename from planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band_smoother.hpp index bc566fdfb96bf..16a4b2bb39db7 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/elastic_band_smoother.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ -#define PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ +#define AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ +#include "autoware_path_smoother/common_structs.hpp" +#include "autoware_path_smoother/elastic_band.hpp" +#include "autoware_path_smoother/replan_checker.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_smoother/common_structs.hpp" -#include "path_smoother/elastic_band.hpp" -#include "path_smoother/replan_checker.hpp" -#include "path_smoother/type_alias.hpp" #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" #include "tier4_autoware_utils/ros/polling_subscriber.hpp" @@ -32,7 +32,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { class ElasticBandSmoother : public rclcpp::Node { @@ -116,6 +116,6 @@ class ElasticBandSmoother : public rclcpp::Node std::unique_ptr published_time_publisher_; }; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__ELASTIC_BAND_SMOOTHER_HPP_ diff --git a/planning/path_smoother/include/path_smoother/replan_checker.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/replan_checker.hpp similarity index 86% rename from planning/path_smoother/include/path_smoother/replan_checker.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/replan_checker.hpp index d06cbc093a0c8..35b0e0102068b 100644 --- a/planning/path_smoother/include/path_smoother/replan_checker.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/replan_checker.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__REPLAN_CHECKER_HPP_ -#define PATH_SMOOTHER__REPLAN_CHECKER_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__REPLAN_CHECKER_HPP_ +#define AUTOWARE_PATH_SMOOTHER__REPLAN_CHECKER_HPP_ -#include "path_smoother/common_structs.hpp" -#include "path_smoother/type_alias.hpp" +#include "autoware_path_smoother/common_structs.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include #include #include -namespace path_smoother +namespace autoware::path_smoother { class ReplanChecker { @@ -66,6 +66,6 @@ class ReplanChecker bool isPathGoalChanged( const PlannerData & planner_data, const std::vector & prev_traj_points) const; }; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__REPLAN_CHECKER_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__REPLAN_CHECKER_HPP_ diff --git a/planning/path_smoother/include/path_smoother/type_alias.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/type_alias.hpp similarity index 86% rename from planning/path_smoother/include/path_smoother/type_alias.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/type_alias.hpp index 21cbcf8e7eefc..dc565d69d3c4d 100644 --- a/planning/path_smoother/include/path_smoother/type_alias.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/type_alias.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__TYPE_ALIAS_HPP_ -#define PATH_SMOOTHER__TYPE_ALIAS_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__TYPE_ALIAS_HPP_ +#define AUTOWARE_PATH_SMOOTHER__TYPE_ALIAS_HPP_ #include "autoware_planning_msgs/msg/path.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" @@ -25,7 +25,7 @@ #include "tier4_debug_msgs/msg/float64_stamped.hpp" #include "tier4_debug_msgs/msg/string_stamped.hpp" -namespace path_smoother +namespace autoware::path_smoother { // std_msgs using std_msgs::msg::Header; @@ -39,6 +39,6 @@ using nav_msgs::msg::Odometry; // debug using tier4_debug_msgs::msg::Float64Stamped; using tier4_debug_msgs::msg::StringStamped; -} // namespace path_smoother +} // namespace autoware::path_smoother -#endif // PATH_SMOOTHER__TYPE_ALIAS_HPP_ +#endif // AUTOWARE_PATH_SMOOTHER__TYPE_ALIAS_HPP_ diff --git a/planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/utils/geometry_utils.hpp similarity index 80% rename from planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/utils/geometry_utils.hpp index 39783b958fa61..6cdf34f319442 100644 --- a/planning/path_smoother/include/path_smoother/utils/geometry_utils.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/utils/geometry_utils.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ -#define PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ +#define AUTOWARE_PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ #include -namespace path_smoother +namespace autoware::path_smoother { namespace geometry_utils { @@ -31,5 +31,5 @@ bool isSamePoint(const T1 & t1, const T2 & t2) return (std::abs(p1.x - p2.x) <= epsilon && std::abs(p1.y - p2.y) <= epsilon); } } // namespace geometry_utils -} // namespace path_smoother -#endif // PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ +} // namespace autoware::path_smoother +#endif // AUTOWARE_PATH_SMOOTHER__UTILS__GEOMETRY_UTILS_HPP_ diff --git a/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp b/planning/autoware_path_smoother/include/autoware_path_smoother/utils/trajectory_utils.hpp similarity index 91% rename from planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp rename to planning/autoware_path_smoother/include/autoware_path_smoother/utils/trajectory_utils.hpp index 55a7829a5bea3..ea717fae20ef4 100644 --- a/planning/path_smoother/include/path_smoother/utils/trajectory_utils.hpp +++ b/planning/autoware_path_smoother/include/autoware_path_smoother/utils/trajectory_utils.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ -#define PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ +#ifndef AUTOWARE_PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ +#define AUTOWARE_PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ +#include "autoware_path_smoother/common_structs.hpp" +#include "autoware_path_smoother/type_alias.hpp" #include "interpolation/linear_interpolation.hpp" #include "interpolation/spline_interpolation.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_smoother/common_structs.hpp" -#include "path_smoother/type_alias.hpp" #include @@ -35,7 +35,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { namespace trajectory_utils { @@ -137,7 +137,7 @@ std::optional updateFrontPointForFix( motion_utils::calcSignedArcLength(points, 0, front_fix_point.pose.position); if (0 < lon_offset_to_prev_front) { RCLCPP_DEBUG( - rclcpp::get_logger("path_smoother.trajectory_utils"), + rclcpp::get_logger("autoware_path_smoother.trajectory_utils"), "Fixed point will not be inserted due to the error during calculation."); return std::nullopt; } @@ -148,7 +148,7 @@ std::optional updateFrontPointForFix( constexpr double max_lat_error = 3.0; if (max_lat_error < dist) { RCLCPP_DEBUG( - rclcpp::get_logger("path_smoother.trajectory_utils"), + rclcpp::get_logger("autoware_path_smoother.trajectory_utils"), "New Fixed point is too far from points %f [m]", dist); } @@ -170,5 +170,5 @@ void insertStopPoint( std::vector & traj_points, const geometry_msgs::msg::Pose & input_stop_pose, const size_t stop_seg_idx); } // namespace trajectory_utils -} // namespace path_smoother -#endif // PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ +} // namespace autoware::path_smoother +#endif // AUTOWARE_PATH_SMOOTHER__UTILS__TRAJECTORY_UTILS_HPP_ diff --git a/planning/path_smoother/launch/elastic_band_smoother.launch.xml b/planning/autoware_path_smoother/launch/elastic_band_smoother.launch.xml similarity index 77% rename from planning/path_smoother/launch/elastic_band_smoother.launch.xml rename to planning/autoware_path_smoother/launch/elastic_band_smoother.launch.xml index db91e1e2dd97d..62658f88df3a4 100644 --- a/planning/path_smoother/launch/elastic_band_smoother.launch.xml +++ b/planning/autoware_path_smoother/launch/elastic_band_smoother.launch.xml @@ -3,9 +3,9 @@ - + - + diff --git a/planning/path_smoother/media/debug/eb_fixed_traj_visualization.png b/planning/autoware_path_smoother/media/debug/eb_fixed_traj_visualization.png similarity index 100% rename from planning/path_smoother/media/debug/eb_fixed_traj_visualization.png rename to planning/autoware_path_smoother/media/debug/eb_fixed_traj_visualization.png diff --git a/planning/path_smoother/media/debug/eb_traj_visualization.png b/planning/autoware_path_smoother/media/debug/eb_traj_visualization.png similarity index 100% rename from planning/path_smoother/media/debug/eb_traj_visualization.png rename to planning/autoware_path_smoother/media/debug/eb_traj_visualization.png diff --git a/planning/path_smoother/media/eb.svg b/planning/autoware_path_smoother/media/eb.svg similarity index 100% rename from planning/path_smoother/media/eb.svg rename to planning/autoware_path_smoother/media/eb.svg diff --git a/planning/path_smoother/media/eb_constraint.svg b/planning/autoware_path_smoother/media/eb_constraint.svg similarity index 100% rename from planning/path_smoother/media/eb_constraint.svg rename to planning/autoware_path_smoother/media/eb_constraint.svg diff --git a/planning/path_smoother/package.xml b/planning/autoware_path_smoother/package.xml similarity index 93% rename from planning/path_smoother/package.xml rename to planning/autoware_path_smoother/package.xml index a0e83fdf8a091..445f8a0e6e736 100644 --- a/planning/path_smoother/package.xml +++ b/planning/autoware_path_smoother/package.xml @@ -1,9 +1,9 @@ - path_smoother + autoware_path_smoother 0.1.0 - The path_smoother package + The autoware_path_smoother package Takayuki Murooka Maxime CLEMENT Apache License 2.0 diff --git a/planning/path_smoother/scripts/calculation_time_plotter.py b/planning/autoware_path_smoother/scripts/calculation_time_plotter.py similarity index 100% rename from planning/path_smoother/scripts/calculation_time_plotter.py rename to planning/autoware_path_smoother/scripts/calculation_time_plotter.py diff --git a/planning/path_smoother/src/elastic_band.cpp b/planning/autoware_path_smoother/src/elastic_band.cpp similarity index 98% rename from planning/path_smoother/src/elastic_band.cpp rename to planning/autoware_path_smoother/src/elastic_band.cpp index 8e538a0d6507f..a443cfd37caec 100644 --- a/planning/path_smoother/src/elastic_band.cpp +++ b/planning/autoware_path_smoother/src/elastic_band.cpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/elastic_band.hpp" +#include "autoware_path_smoother/elastic_band.hpp" +#include "autoware_path_smoother/type_alias.hpp" +#include "autoware_path_smoother/utils/geometry_utils.hpp" +#include "autoware_path_smoother/utils/trajectory_utils.hpp" #include "motion_utils/trajectory/conversion.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_smoother/type_alias.hpp" -#include "path_smoother/utils/geometry_utils.hpp" -#include "path_smoother/utils/trajectory_utils.hpp" #include "tf2/utils.h" #include @@ -84,7 +84,7 @@ std_msgs::msg::Header createHeader(const rclcpp::Time & now) } } // namespace -namespace path_smoother +namespace autoware::path_smoother { EBPathSmoother::EBParam::EBParam(rclcpp::Node * node) { @@ -453,4 +453,4 @@ std::optional> EBPathSmoother::convertOptimizedPoin time_keeper_ptr_->toc(__func__, " "); return eb_traj_points; } -} // namespace path_smoother +} // namespace autoware::path_smoother diff --git a/planning/path_smoother/src/elastic_band_smoother.cpp b/planning/autoware_path_smoother/src/elastic_band_smoother.cpp similarity index 97% rename from planning/path_smoother/src/elastic_band_smoother.cpp rename to planning/autoware_path_smoother/src/elastic_band_smoother.cpp index 75300286ac9dc..2f507c8bae311 100644 --- a/planning/path_smoother/src/elastic_band_smoother.cpp +++ b/planning/autoware_path_smoother/src/elastic_band_smoother.cpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/elastic_band_smoother.hpp" +#include "autoware_path_smoother/elastic_band_smoother.hpp" +#include "autoware_path_smoother/utils/geometry_utils.hpp" +#include "autoware_path_smoother/utils/trajectory_utils.hpp" #include "interpolation/spline_interpolation_points_2d.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "path_smoother/utils/geometry_utils.hpp" -#include "path_smoother/utils/trajectory_utils.hpp" #include "rclcpp/time.hpp" #include #include -namespace path_smoother +namespace autoware::path_smoother { namespace { @@ -70,7 +70,7 @@ bool hasZeroVelocity(const TrajectoryPoint & traj_point) } // namespace ElasticBandSmoother::ElasticBandSmoother(const rclcpp::NodeOptions & node_options) -: Node("path_smoother", node_options), time_keeper_ptr_(std::make_shared()) +: Node("autoware_path_smoother", node_options), time_keeper_ptr_(std::make_shared()) { // interface publisher traj_pub_ = create_publisher("~/output/traj", 1); @@ -384,7 +384,7 @@ std::vector ElasticBandSmoother::extendTrajectory( time_keeper_ptr_->toc(__func__, " "); return resampled_traj_points; } -} // namespace path_smoother +} // namespace autoware::path_smoother #include "rclcpp_components/register_node_macro.hpp" -RCLCPP_COMPONENTS_REGISTER_NODE(path_smoother::ElasticBandSmoother) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::path_smoother::ElasticBandSmoother) diff --git a/planning/path_smoother/src/replan_checker.cpp b/planning/autoware_path_smoother/src/replan_checker.cpp similarity index 97% rename from planning/path_smoother/src/replan_checker.cpp rename to planning/autoware_path_smoother/src/replan_checker.cpp index f451a05a8f835..4e5911ea5b42e 100644 --- a/planning/path_smoother/src/replan_checker.cpp +++ b/planning/autoware_path_smoother/src/replan_checker.cpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/replan_checker.hpp" +#include "autoware_path_smoother/replan_checker.hpp" +#include "autoware_path_smoother/utils/trajectory_utils.hpp" #include "motion_utils/trajectory/trajectory.hpp" -#include "path_smoother/utils/trajectory_utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" #include -namespace path_smoother +namespace autoware::path_smoother { ReplanChecker::ReplanChecker(rclcpp::Node * node, const EgoNearestParam & ego_nearest_param) : ego_nearest_param_(ego_nearest_param), logger_(node->get_logger().get_child("replan_checker")) @@ -208,4 +208,4 @@ bool ReplanChecker::isPathGoalChanged( return true; } -} // namespace path_smoother +} // namespace autoware::path_smoother diff --git a/planning/path_smoother/src/utils/trajectory_utils.cpp b/planning/autoware_path_smoother/src/utils/trajectory_utils.cpp similarity index 94% rename from planning/path_smoother/src/utils/trajectory_utils.cpp rename to planning/autoware_path_smoother/src/utils/trajectory_utils.cpp index b4d0950a593d5..5fea20c9a405f 100644 --- a/planning/path_smoother/src/utils/trajectory_utils.cpp +++ b/planning/autoware_path_smoother/src/utils/trajectory_utils.cpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/utils/trajectory_utils.hpp" +#include "autoware_path_smoother/utils/trajectory_utils.hpp" +#include "autoware_path_smoother/utils/geometry_utils.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "path_smoother/utils/geometry_utils.hpp" #include "autoware_planning_msgs/msg/path_point.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" @@ -30,7 +30,7 @@ #include #include -namespace path_smoother +namespace autoware::path_smoother { namespace trajectory_utils { @@ -98,4 +98,4 @@ void insertStopPoint( traj_points.insert(traj_points.begin() + stop_seg_idx + 1, additional_traj_point); } } // namespace trajectory_utils -} // namespace path_smoother +} // namespace autoware::path_smoother diff --git a/planning/path_smoother/test/test_path_smoother_node_interface.cpp b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp similarity index 76% rename from planning/path_smoother/test/test_path_smoother_node_interface.cpp rename to planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp index 30e9fba1433cb..41c48630c8f8c 100644 --- a/planning/path_smoother/test/test_path_smoother_node_interface.cpp +++ b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "path_smoother/elastic_band_smoother.hpp" +#include "autoware_path_smoother/elastic_band_smoother.hpp" #include #include @@ -32,24 +32,26 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto path_smoothing_dir = ament_index_cpp::get_package_share_directory("path_smoother"); + const auto path_smoothing_dir = + ament_index_cpp::get_package_share_directory("autoware_path_smoother"); node_options.arguments( {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_common.param.yaml", "--params-file", planning_test_utils_dir + "/config/test_nearest_search.param.yaml", "--params-file", path_smoothing_dir + "/config/elastic_band_smoother.param.yaml"}); - auto test_target_node = std::make_shared(node_options); + auto test_target_node = + std::make_shared(node_options); // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "path_smoother/input/odometry"); + test_manager->publishOdometry(test_target_node, "autoware_path_smoother/input/odometry"); // set subscriber with topic name - test_manager->setTrajectorySubscriber("path_smoother/output/traj"); - test_manager->setPathSubscriber("path_smoother/output/path"); + test_manager->setTrajectorySubscriber("autoware_path_smoother/output/traj"); + test_manager->setPathSubscriber("autoware_path_smoother/output/path"); // set input topic name (this topic is changed to test node) - test_manager->setPathInputTopicName("path_smoother/input/path"); + test_manager->setPathInputTopicName("autoware_path_smoother/input/path"); // test with normal trajectory ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPath(test_target_node)); diff --git a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml index 486ea547e3dc1..3d786ab995e5b 100644 --- a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -28,7 +28,7 @@ default="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml" /> - + diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index 4cf19c1da0e6a..26eb41ca1de23 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -18,6 +18,7 @@ autoware_behavior_path_planner_common autoware_map_msgs autoware_path_optimizer + autoware_path_smoother autoware_perception_msgs autoware_planning_msgs geography_utils @@ -30,7 +31,6 @@ mission_planner motion_utils osqp_interface - path_smoother rclcpp rclcpp_components route_handler diff --git a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp index 0705f0b51ddd3..7dd3a20848aca 100644 --- a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -15,9 +15,9 @@ #include "centerline_source/optimization_trajectory_based_centerline.hpp" #include "autoware_path_optimizer/node.hpp" +#include "autoware_path_smoother/elastic_band_smoother.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "path_smoother/elastic_band_smoother.hpp" #include "static_centerline_generator_node.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "utils.hpp" @@ -128,7 +128,7 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra // create an instance of elastic band and model predictive trajectory. const auto eb_path_smoother_ptr = - path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); + autoware::path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); const auto mpt_optimizer_ptr = autoware::path_optimizer::PathOptimizer(create_node_options()).getMPTOptimizer(); @@ -152,7 +152,7 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra virtual_ego_pose_offset_idx) .pose; - // smooth trajectory by elastic band in the path_smoother package + // smooth trajectory by elastic band in the autoware_path_smoother package const auto smoothed_traj_points = eb_path_smoother_ptr->smoothTrajectory(raw_traj_points, virtual_ego_pose); diff --git a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py index 7a5cdfd905fe9..6316afc8cb3dc 100644 --- a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py +++ b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py @@ -63,7 +63,7 @@ def generate_test_description(): "config/behavior_velocity_planner.param.yaml", ), os.path.join( - get_package_share_directory("path_smoother"), + get_package_share_directory("autoware_path_smoother"), "config/elastic_band_smoother.param.yaml", ), os.path.join(