diff --git a/planning/static_centerline_generator/CMakeLists.txt b/planning/static_centerline_generator/CMakeLists.txt index 991d12097cc08..3993674c89e8c 100644 --- a/planning/static_centerline_generator/CMakeLists.txt +++ b/planning/static_centerline_generator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(static_centerline_generator) +project(autoware_static_centerline_generator) find_package(autoware_cmake REQUIRED) @@ -9,7 +9,7 @@ find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) rosidl_generate_interfaces( - static_centerline_generator + autoware_static_centerline_generator "srv/LoadMap.srv" "srv/PlanRoute.srv" "srv/PlanPath.srv" @@ -29,10 +29,10 @@ ament_auto_add_executable(main if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) rosidl_target_interfaces(main - static_centerline_generator "rosidl_typesupport_cpp") + autoware_static_centerline_generator "rosidl_typesupport_cpp") else() rosidl_get_typesupport_target( - cpp_typesupport_target static_centerline_generator "rosidl_typesupport_cpp") + cpp_typesupport_target autoware_static_centerline_generator "rosidl_typesupport_cpp") target_link_libraries(main "${cpp_typesupport_target}") endif() diff --git a/planning/static_centerline_generator/README.md b/planning/static_centerline_generator/README.md index 00572b754645c..844d0af15f2a5 100644 --- a/planning/static_centerline_generator/README.md +++ b/planning/static_centerline_generator/README.md @@ -34,7 +34,7 @@ We can run with the following command by designating `` ```sh -ros2 launch static_centerline_generator run_planning_server.launch.xml vehicle_model:= +ros2 launch autoware_static_centerline_generator run_planning_server.launch.xml vehicle_model:= ``` FYI, port ID of the http server is 4010 by default. @@ -50,7 +50,7 @@ The optimized centerline can be generated from the command line interface by des - `` ```sh -ros2 launch static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:= lanelet2_output_file_path:= start_lanelet_id:= end_lanelet_id:= vehicle_model:= +ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:= lanelet2_output_file_path:= start_lanelet_id:= end_lanelet_id:= vehicle_model:= ``` The default output map path containing the optimized centerline locates `/tmp/lanelet2_map.osm`. diff --git a/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp index 30b2e55c36bba..912194004286d 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp @@ -20,8 +20,8 @@ #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { std::vector generate_centerline_with_bag(rclcpp::Node & node); -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator #endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ diff --git a/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp index 7e7cdea31e9f1..c20da46f1375b 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp @@ -20,7 +20,7 @@ #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { class OptimizationTrajectoryBasedCenterline { @@ -37,7 +37,7 @@ class OptimizationTrajectoryBasedCenterline rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; }; -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator // clang-format off #endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT // clang-format on diff --git a/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp b/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp index c1d92c06a8e05..6ba3d087d1532 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp @@ -17,9 +17,9 @@ #include "rclcpp/rclcpp.hpp" #include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp" -#include "static_centerline_generator/srv/load_map.hpp" -#include "static_centerline_generator/srv/plan_path.hpp" -#include "static_centerline_generator/srv/plan_route.hpp" +#include "autoware_static_centerline_generator/srv/load_map.hpp" +#include "autoware_static_centerline_generator/srv/plan_path.hpp" +#include "autoware_static_centerline_generator/srv/plan_route.hpp" #include "static_centerline_generator/type_alias.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" @@ -34,11 +34,11 @@ #include #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { -using static_centerline_generator::srv::LoadMap; -using static_centerline_generator::srv::PlanPath; -using static_centerline_generator::srv::PlanRoute; +using autoware_static_centerline_generator::srv::LoadMap; +using autoware_static_centerline_generator::srv::PlanPath; +using autoware_static_centerline_generator::srv::PlanRoute; struct CenterlineWithRoute { @@ -115,5 +115,5 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node // vehicle info vehicle_info_util::VehicleInfo vehicle_info_; }; -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator #endif // STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ diff --git a/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp b/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp index 2dcb9cbbd099f..8fddef2c28842 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp @@ -26,7 +26,7 @@ #include "autoware_planning_msgs/msg/lanelet_route.hpp" #include "visualization_msgs/msg/marker_array.hpp" -namespace static_centerline_generator +namespace autoware::static_centerline_generator { using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_perception_msgs::msg::PredictedObjects; @@ -41,6 +41,6 @@ using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Point2d; using visualization_msgs::msg::MarkerArray; -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator #endif // STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ diff --git a/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp b/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp index c8cf8f8b90590..9b755f80a6888 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp @@ -24,7 +24,7 @@ #include #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { namespace utils { @@ -53,6 +53,6 @@ MarkerArray create_distance_text_marker( const geometry_msgs::msg::Pose & pose, const double dist, const std::array & marker_color, const rclcpp::Time & now, const size_t idx); } // namespace utils -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator #endif // STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ diff --git a/planning/static_centerline_generator/launch/run_planning_server.launch.xml b/planning/static_centerline_generator/launch/run_planning_server.launch.xml index 1493078317458..cb368ca336316 100644 --- a/planning/static_centerline_generator/launch/run_planning_server.launch.xml +++ b/planning/static_centerline_generator/launch/run_planning_server.launch.xml @@ -2,11 +2,11 @@ - + - + diff --git a/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml index ae71b0ae6e925..09868758f798a 100644 --- a/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -55,7 +55,7 @@ - + @@ -79,11 +79,11 @@ - + - + diff --git a/planning/static_centerline_generator/package.xml b/planning/static_centerline_generator/package.xml index 6573f6e439c43..96e17595d49ee 100644 --- a/planning/static_centerline_generator/package.xml +++ b/planning/static_centerline_generator/package.xml @@ -1,9 +1,9 @@ - static_centerline_generator + autoware_static_centerline_generator 0.1.0 - The static_centerline_generator package + The autoware_static_centerline_generator package Takayuki Murooka Kosuke Takeuchi Apache License 2.0 diff --git a/planning/static_centerline_generator/rviz/static_centerline_generator.rviz b/planning/static_centerline_generator/rviz/static_centerline_generator.rviz index 62b4c9b75ec87..002af580c2f00 100644 --- a/planning/static_centerline_generator/rviz/static_centerline_generator.rviz +++ b/planning/static_centerline_generator/rviz/static_centerline_generator.rviz @@ -130,7 +130,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/input_centerline + Value: /autoware_static_centerline_generator/input_centerline Value: true View Drivable Area: Alpha: 0.9990000128746033 @@ -179,7 +179,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/output_centerline + Value: /autoware_static_centerline_generator/output_centerline Value: true View Footprint: Alpha: 1 @@ -222,7 +222,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/debug/raw_centerline + Value: /autoware_static_centerline_generator/debug/raw_centerline Value: false View Drivable Area: Alpha: 0.9990000128746033 @@ -268,7 +268,7 @@ Visualization Manager: Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/debug/unsafe_footprints + Value: /autoware_static_centerline_generator/debug/unsafe_footprints Value: true Enabled: false Name: debug diff --git a/planning/static_centerline_generator/scripts/app.py b/planning/static_centerline_generator/scripts/app.py index c1cb0473da040..e13ba87953ef9 100755 --- a/planning/static_centerline_generator/scripts/app.py +++ b/planning/static_centerline_generator/scripts/app.py @@ -23,9 +23,9 @@ from flask_cors import CORS import rclpy from rclpy.node import Node -from static_centerline_generator.srv import LoadMap -from static_centerline_generator.srv import PlanPath -from static_centerline_generator.srv import PlanRoute +from autoware_static_centerline_generator.srv import LoadMap +from autoware_static_centerline_generator.srv import PlanPath +from autoware_static_centerline_generator.srv import PlanRoute rclpy.init() node = Node("static_centerline_generator_http_server") @@ -51,7 +51,7 @@ def get_map(): map_id = map_uuid # create client - cli = create_client(LoadMap, "/planning/static_centerline_generator/load_map") + cli = create_client(LoadMap, "/planning/autoware_static_centerline_generator/load_map") # request map loading req = LoadMap.Request(map=data["map"]) @@ -85,7 +85,7 @@ def post_planned_route(): print("map_id is not correct.") # create client - cli = create_client(PlanRoute, "/planning/static_centerline_generator/plan_route") + cli = create_client(PlanRoute, "/planning/autoware_static_centerline_generator/plan_route") # request route planning req = PlanRoute.Request( @@ -123,7 +123,7 @@ def post_planned_path(): print("map_id is not correct.") # create client - cli = create_client(PlanPath, "/planning/static_centerline_generator/plan_path") + cli = create_client(PlanPath, "/planning/autoware_static_centerline_generator/plan_path") # request path planning route_lane_ids = [eval(i) for i in request.args.getlist("route[]")] diff --git a/planning/static_centerline_generator/scripts/centerline_updater_helper.py b/planning/static_centerline_generator/scripts/centerline_updater_helper.py index fec3d21d20bec..cec4e5b457c7f 100755 --- a/planning/static_centerline_generator/scripts/centerline_updater_helper.py +++ b/planning/static_centerline_generator/scripts/centerline_updater_helper.py @@ -155,7 +155,7 @@ def __init__(self): transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) self.sub_whole_centerline = self.create_subscription( Trajectory, - "/static_centerline_generator/output_whole_centerline", + "/autoware_static_centerline_generator/output_whole_centerline", self.onWholeCenterline, transient_local_qos, ) diff --git a/planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py b/planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py index 912226511f1d9..00d06ca2213d1 100755 --- a/planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py +++ b/planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py @@ -98,8 +98,8 @@ def remove_diff_to_ignore(osm_root): ) args = parser.parse_args() - original_osm_file_name = "/tmp/static_centerline_generator/input/lanelet2_map.osm" - modified_osm_file_name = "/tmp/static_centerline_generator/output/lanelet2_map.osm" + original_osm_file_name = "/tmp/autoware_static_centerline_generator/input/lanelet2_map.osm" + modified_osm_file_name = "/tmp/autoware_static_centerline_generator/output/lanelet2_map.osm" # load LL2 maps original_osm_tree = ET.parse(original_osm_file_name) @@ -118,7 +118,7 @@ def remove_diff_to_ignore(osm_root): remove_diff_to_ignore(modified_osm_root) # write LL2 maps - output_dir_path = "/tmp/static_centerline_generator/show_lanelet2_map_diff/" + output_dir_path = "/tmp/autoware_static_centerline_generator/show_lanelet2_map_diff/" os.makedirs(output_dir_path + "original/", exist_ok=True) os.makedirs(output_dir_path + "modified/", exist_ok=True) diff --git a/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh index 30ed667dd3732..e7f86062a9d20 100755 --- a/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh +++ b/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh @@ -1,3 +1,3 @@ #!/bin/bash -ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_generator --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus +ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix autoware_static_centerline_generator --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus diff --git a/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh b/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh index 809bbb46a179e..488091989d1fa 100755 --- a/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh +++ b/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh @@ -1,3 +1,3 @@ #!/bin/bash -ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus +ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp index 4e541b1aff527..48be274aa0543 100644 --- a/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp +++ b/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -20,7 +20,7 @@ #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { std::vector generate_centerline_with_bag(rclcpp::Node & node) { @@ -79,4 +79,4 @@ std::vector generate_centerline_with_bag(rclcpp::Node & node) return centerline_traj_points; } -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator diff --git a/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp index 7980ae4e8d2d7..3c22740cd10d5 100644 --- a/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ b/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -22,7 +22,7 @@ #include "static_centerline_generator/utils.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" -namespace static_centerline_generator +namespace autoware::static_centerline_generator { namespace { @@ -180,4 +180,4 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra return whole_optimized_traj_points; } -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator diff --git a/planning/static_centerline_generator/src/main.cpp b/planning/static_centerline_generator/src/main.cpp index 981cf54fc9274..ea68ef81e7b76 100644 --- a/planning/static_centerline_generator/src/main.cpp +++ b/planning/static_centerline_generator/src/main.cpp @@ -21,7 +21,7 @@ int main(int argc, char * argv[]) // initialize node rclcpp::NodeOptions node_options; auto node = - std::make_shared(node_options); + std::make_shared(node_options); // get ros parameter const bool run_background = node->declare_parameter("run_background"); diff --git a/planning/static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/static_centerline_generator/src/static_centerline_generator_node.cpp index 750b2e68b16b0..48ad7274a4dbe 100644 --- a/planning/static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/static_centerline_generator/src/static_centerline_generator_node.cpp @@ -22,7 +22,7 @@ #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" #include "static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp" -#include "static_centerline_generator/msg/points_with_lane_id.hpp" +#include "autoware_static_centerline_generator/msg/points_with_lane_id.hpp" #include "static_centerline_generator/type_alias.hpp" #include "static_centerline_generator/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -54,7 +54,7 @@ #include #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { namespace { @@ -168,7 +168,7 @@ std::vector resample_trajectory_points( StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( const rclcpp::NodeOptions & node_options) -: Node("static_centerline_generator", node_options) +: Node("autoware_static_centerline_generator", node_options) { // publishers pub_map_bin_ = @@ -216,19 +216,19 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); srv_load_map_ = create_service( - "/planning/static_centerline_generator/load_map", + "/planning/autoware_static_centerline_generator/load_map", std::bind( &StaticCenterlineGeneratorNode::on_load_map, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_route_ = create_service( - "/planning/static_centerline_generator/plan_route", + "/planning/autoware_static_centerline_generator/plan_route", std::bind( &StaticCenterlineGeneratorNode::on_plan_route, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_path_ = create_service( - "/planning/static_centerline_generator/plan_path", + "/planning/autoware_static_centerline_generator/plan_path", std::bind( &StaticCenterlineGeneratorNode::on_plan_path, this, std::placeholders::_1, std::placeholders::_2), @@ -246,7 +246,7 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( return CenterlineSource::BagEgoTrajectoryBase; } throw std::logic_error( - "The centerline source is not supported in static_centerline_generator."); + "The centerline source is not supported in autoware_static_centerline_generator."); }(); } @@ -318,7 +318,7 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout return CenterlineWithRoute{bag_centerline, route_lane_ids}; } throw std::logic_error( - "The centerline source is not supported in static_centerline_generator."); + "The centerline source is not supported in autoware_static_centerline_generator."); }(); // resample @@ -338,7 +338,7 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_file_path) { // copy the input LL2 map to the temporary file for debugging - const std::string debug_input_file_dir{"/tmp/static_centerline_generator/input/"}; + const std::string debug_input_file_dir{"/tmp/autoware_static_centerline_generator/input/"}; std::filesystem::create_directories(debug_input_file_dir); std::filesystem::copy( lanelet2_input_file_path, debug_input_file_dir + "lanelet2_map.osm", @@ -541,7 +541,7 @@ void StaticCenterlineGeneratorNode::on_plan_path( if (!current_lanelet_points.empty()) { // register points with lane_id - static_centerline_generator::msg::PointsWithLaneId points_with_lane_id; + autoware_static_centerline_generator::msg::PointsWithLaneId points_with_lane_id; points_with_lane_id.lane_id = lanelet.id(); points_with_lane_id.points = current_lanelet_points; response->points_with_lane_ids.push_back(points_with_lane_id); @@ -645,10 +645,10 @@ void StaticCenterlineGeneratorNode::save_map( RCLCPP_INFO(get_logger(), "Saved map."); // copy the output LL2 map to the temporary file for debugging - const std::string debug_output_file_dir{"/tmp/static_centerline_generator/output/"}; + const std::string debug_output_file_dir{"/tmp/autoware_static_centerline_generator/output/"}; std::filesystem::create_directories(debug_output_file_dir); std::filesystem::copy( lanelet2_output_file_path, debug_output_file_dir + "lanelet2_map.osm", std::filesystem::copy_options::overwrite_existing); } -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator diff --git a/planning/static_centerline_generator/src/utils.cpp b/planning/static_centerline_generator/src/utils.cpp index ddfd3e11036ce..c3678a4b2349b 100644 --- a/planning/static_centerline_generator/src/utils.cpp +++ b/planning/static_centerline_generator/src/utils.cpp @@ -21,7 +21,7 @@ #include #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { namespace { @@ -228,4 +228,4 @@ MarkerArray create_distance_text_marker( return marker_array; } } // namespace utils -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator diff --git a/planning/static_centerline_generator/srv/PlanPath.srv b/planning/static_centerline_generator/srv/PlanPath.srv index 7d823b4eccbf9..3a8d0321ffb9a 100644 --- a/planning/static_centerline_generator/srv/PlanPath.srv +++ b/planning/static_centerline_generator/srv/PlanPath.srv @@ -1,6 +1,6 @@ uint32 map_id int64[] route --- -static_centerline_generator/PointsWithLaneId[] points_with_lane_ids +autoware_static_centerline_generator/PointsWithLaneId[] points_with_lane_ids string message int64[] unconnected_lane_ids diff --git a/planning/static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/static_centerline_generator/test/test_static_centerline_generator.test.py index 29ee49a11e3b3..bde33117d8cc7 100644 --- a/planning/static_centerline_generator/test/test_static_centerline_generator.test.py +++ b/planning/static_centerline_generator/test/test_static_centerline_generator.test.py @@ -28,11 +28,11 @@ @pytest.mark.launch_test def generate_test_description(): lanelet2_map_path = os.path.join( - get_package_share_directory("static_centerline_generator"), "test/data/lanelet2_map.osm" + get_package_share_directory("autoware_static_centerline_generator"), "test/data/lanelet2_map.osm" ) static_centerline_generator_node = Node( - package="static_centerline_generator", + package="autoware_static_centerline_generator", executable="main", output="screen", parameters=[ @@ -50,8 +50,8 @@ def generate_test_description(): "mission_planner.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_generator"), - "config/static_centerline_generator.param.yaml", + get_package_share_directory("autoware_static_centerline_generator"), + "config/autoware_static_centerline_generator.param.yaml", ), os.path.join( get_package_share_directory("behavior_path_planner"), @@ -74,15 +74,15 @@ def generate_test_description(): "config/lanelet2_map_loader.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_generator"), + get_package_share_directory("autoware_static_centerline_generator"), "config/common.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_generator"), + get_package_share_directory("autoware_static_centerline_generator"), "config/nearest_search.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_generator"), + get_package_share_directory("autoware_static_centerline_generator"), "config/vehicle_info.param.yaml", ), ], @@ -94,7 +94,7 @@ def generate_test_description(): LaunchDescription( [ static_centerline_generator_node, - # Start test after 1s - gives time for the static_centerline_generator to finish initialization + # Start test after 1s - gives time for the autoware_static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ),