From 6137908a09af072c5434f9cfa8c6d8c90ef096dc Mon Sep 17 00:00:00 2001 From: cyn-liu <104069308+cyn-liu@users.noreply.github.com> Date: Wed, 22 Nov 2023 17:34:26 +0800 Subject: [PATCH] feat(autoware.universe): replace autoware_auto_mapping_msg with autoware_map_msg (#5615) * feat(autoware.universe): replace autoware_auto_mapping_msg with autoware_map_msg Signed-off-by: liu cui * style(pre-commit): autofix --------- Signed-off-by: liu cui Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../package.xml | 2 +- .../src/traffic_light_publish_panel.cpp | 4 ++-- .../src/traffic_light_publish_panel.hpp | 8 ++++---- .../Readme.md | 2 +- .../package.xml | 2 +- ...ffic_light_recognition_marker_publisher.cpp | 4 ++-- ...ffic_light_recognition_marker_publisher.hpp | 8 ++++---- control/lane_departure_checker/README.md | 2 +- .../lane_departure_checker_node.hpp | 8 ++++---- control/lane_departure_checker/package.xml | 2 +- .../lane_departure_checker_node.cpp | 4 ++-- .../ar_tag_based_localizer/README.md | 2 +- .../src/ar_tag_based_localizer.cpp | 4 ++-- .../src/ar_tag_based_localizer.hpp | 6 +++--- .../landmark_manager/landmark_manager.hpp | 4 ++-- .../landmark_manager/package.xml | 2 +- .../landmark_manager/src/landmark_manager.cpp | 8 ++++---- localization/yabloc/yabloc_common/README.md | 14 +++++++------- .../ground_server/ground_server.hpp | 8 ++++---- .../ll2_decomposer/ll2_decomposer.hpp | 8 ++++---- localization/yabloc/yabloc_common/package.xml | 2 +- .../src/ground_server/ground_server_core.cpp | 4 ++-- .../src/ll2_decomposer/ll2_decomposer_core.cpp | 4 ++-- .../yabloc/yabloc_pose_initializer/README.md | 10 +++++----- .../camera/camera_pose_initializer.hpp | 8 ++++---- .../yabloc/yabloc_pose_initializer/package.xml | 2 +- .../camera/camera_pose_initializer_core.cpp | 4 ++-- map/map_loader/README.md | 8 ++++---- .../map_loader/lanelet2_map_loader_node.hpp | 8 ++++---- .../lanelet2_map_visualization_node.hpp | 6 +++--- map/map_loader/package.xml | 1 - .../lanelet2_map_loader_node.cpp | 10 +++++----- .../lanelet2_map_visualization_node.cpp | 6 +++--- map/map_tf_generator/Readme.md | 6 +++--- .../src/vector_map_tf_generator_node.cpp | 8 ++++---- .../README.md | 2 +- .../crosswalk_traffic_light_estimator/node.hpp | 8 ++++---- .../package.xml | 2 +- .../src/node.cpp | 4 ++-- .../object_lanelet_filter.hpp | 6 +++--- .../object_position_filter.hpp | 2 +- .../object-lanelet-filter.md | 2 +- .../detected_object_validation/package.xml | 2 +- .../src/object_lanelet_filter.cpp | 4 ++-- perception/elevation_map_loader/README.md | 2 +- .../elevation_map_loader_node.hpp | 6 +++--- perception/elevation_map_loader/package.xml | 1 - .../src/elevation_map_loader_node.cpp | 4 ++-- perception/map_based_prediction/README.md | 2 +- .../map_based_prediction_node.hpp | 8 ++++---- .../src/map_based_prediction_node.cpp | 4 ++-- .../radar_object_tracker_node.hpp | 8 ++++---- .../radar_object_tracker_node.cpp | 4 ++-- perception/traffic_light_arbiter/README.md | 2 +- .../traffic_light_arbiter.hpp | 4 ++-- perception/traffic_light_arbiter/package.xml | 2 +- .../traffic_light_map_based_detector/README.md | 2 +- .../traffic_light_map_based_detector/node.hpp | 6 +++--- .../package.xml | 2 +- .../src/node.cpp | 4 ++-- .../traffic_light_multi_camera_fusion/node.hpp | 6 +++--- .../package.xml | 2 +- .../src/node.cpp | 4 ++-- .../README.md | 2 +- .../nodelet.hpp | 6 +++--- .../package.xml | 2 +- .../src/nodelet.cpp | 4 ++-- .../traffic_light_visualization/README.md | 2 +- .../traffic_light_map_visualizer/node.hpp | 7 +++---- .../src/traffic_light_map_visualizer/node.cpp | 4 ++-- planning/behavior_path_planner/README.md | 4 ++-- .../behavior_path_planner_node.hpp | 10 +++++----- .../test/test_drivable_area_expansion.cpp | 2 +- planning/behavior_velocity_planner/README.md | 2 +- planning/behavior_velocity_planner/package.xml | 2 +- .../behavior_velocity_planner/src/node.cpp | 4 ++-- .../behavior_velocity_planner/src/node.hpp | 10 +++++----- .../src/planner_manager.hpp | 2 +- .../planner_data.hpp | 2 +- .../package.xml | 2 +- planning/costmap_generator/README.md | 2 +- .../costmap_generator/costmap_generator.hpp | 6 +++--- .../costmap_generator_node.cpp | 4 ++-- planning/costmap_generator/package.xml | 2 +- planning/mission_planner/README.md | 10 +++++----- .../mission_planner/mission_planner_plugin.hpp | 6 +++--- .../src/lanelet2_plugins/default_planner.cpp | 6 +++--- .../src/lanelet2_plugins/default_planner.hpp | 8 ++++---- .../src/mission_planner/mission_planner.cpp | 6 +++--- .../src/mission_planner/mission_planner.hpp | 8 ++++---- planning/obstacle_stop_planner/README.md | 2 +- planning/obstacle_velocity_limiter/README.md | 2 +- .../obstacle_velocity_limiter_node.hpp | 4 ++-- .../src/obstacle_velocity_limiter_node.cpp | 4 ++-- .../planning_interface_test_manager.hpp | 6 +++--- .../planning_interface_test_manager_utils.hpp | 18 +++++++++--------- planning/planning_test_utils/package.xml | 2 +- .../include/route_handler/route_handler.hpp | 8 ++++---- planning/route_handler/package.xml | 2 +- planning/route_handler/src/route_handler.cpp | 4 ++-- planning/scenario_selector/README.md | 2 +- .../scenario_selector_node.hpp | 6 +++--- planning/scenario_selector/package.xml | 2 +- .../scenario_selector_node.cpp | 5 ++--- .../static_centerline_optimizer/type_alias.hpp | 4 ++-- .../static_centerline_optimizer/package.xml | 2 +- .../src/static_centerline_optimizer_node.cpp | 7 ++++--- .../docs/vector-map-filter.md | 8 ++++---- .../docs/vector-map-inside-area-filter.md | 8 ++++---- .../lanelet2_map_filter_nodelet.hpp | 6 +++--- .../vector_map_inside_area_filter.hpp | 4 ++-- .../lanelet2_map_filter_nodelet.cpp | 4 ++-- .../vector_map_inside_area_filter.cpp | 4 ++-- .../simple_planning_simulator_core.hpp | 8 ++++---- .../simple_planning_simulator/package.xml | 2 +- .../simple_planning_simulator_core.cpp | 4 ++-- .../simulator_compatibility_test/package.xml | 2 +- 117 files changed, 273 insertions(+), 276 deletions(-) diff --git a/common/tier4_traffic_light_rviz_plugin/package.xml b/common/tier4_traffic_light_rviz_plugin/package.xml index 2b118b429f1af..b123f8e2bdc3c 100644 --- a/common/tier4_traffic_light_rviz_plugin/package.xml +++ b/common/tier4_traffic_light_rviz_plugin/package.xml @@ -10,7 +10,7 @@ ament_cmake_auto autoware_cmake - autoware_auto_mapping_msgs + autoware_map_msgs autoware_perception_msgs lanelet2_extension libqt5-core diff --git a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp index 35c5a88a2f8a6..4433730c8ac68 100644 --- a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp +++ b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp @@ -221,7 +221,7 @@ void TrafficLightPublishPanel::onInitialize() pub_traffic_signals_ = raw_node_->create_publisher( "/perception/traffic_light_recognition/traffic_signals", rclcpp::QoS(1)); - sub_vector_map_ = raw_node_->create_subscription( + sub_vector_map_ = raw_node_->create_subscription( "/map/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&TrafficLightPublishPanel::onVectorMap, this, _1)); createWallTimer(); @@ -361,7 +361,7 @@ void TrafficLightPublishPanel::onTimer() traffic_table_->update(); } -void TrafficLightPublishPanel::onVectorMap(const HADMapBin::ConstSharedPtr msg) +void TrafficLightPublishPanel::onVectorMap(const LaneletMapBin::ConstSharedPtr msg) { if (received_vector_map_) return; // NOTE: examples from map_loader/lanelet2_map_visualization_node.cpp diff --git a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp index e54b6a301873b..b10faee8f6aa8 100644 --- a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp +++ b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp @@ -26,7 +26,7 @@ #include #include -#include +#include #include #endif @@ -35,7 +35,7 @@ namespace rviz_plugins { -using autoware_auto_mapping_msgs::msg::HADMapBin; +using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::TrafficSignal; using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_perception_msgs::msg::TrafficSignalElement; @@ -56,12 +56,12 @@ public Q_SLOTS: protected: void onTimer(); void createWallTimer(); - void onVectorMap(const HADMapBin::ConstSharedPtr msg); + void onVectorMap(const LaneletMapBin::ConstSharedPtr msg); rclcpp::Node::SharedPtr raw_node_; rclcpp::TimerBase::SharedPtr pub_timer_; rclcpp::Publisher::SharedPtr pub_traffic_signals_; - rclcpp::Subscription::SharedPtr sub_vector_map_; + rclcpp::Subscription::SharedPtr sub_vector_map_; QSpinBox * publishing_rate_input_; QComboBox * traffic_light_id_input_; diff --git a/common/traffic_light_recognition_marker_publisher/Readme.md b/common/traffic_light_recognition_marker_publisher/Readme.md index 1cafc619ff6fb..3f9e9214c3e84 100644 --- a/common/traffic_light_recognition_marker_publisher/Readme.md +++ b/common/traffic_light_recognition_marker_publisher/Readme.md @@ -14,7 +14,7 @@ This node publishes a marker array for visualizing traffic signal recognition re | Name | Type | Description | | ------------------------------------------------------- | -------------------------------------------------------- | ------------------------------------------------- | -| `/map/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | Vector map for getting traffic signal information | +| `/map/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | Vector map for getting traffic signal information | | `/perception/traffic_light_recognition/traffic_signals` | `autoware_auto_perception_msgs::msg::TrafficSignalArray` | The result of traffic signal recognition | ### Output diff --git a/common/traffic_light_recognition_marker_publisher/package.xml b/common/traffic_light_recognition_marker_publisher/package.xml index d12022c01684e..fe416b13520dd 100644 --- a/common/traffic_light_recognition_marker_publisher/package.xml +++ b/common/traffic_light_recognition_marker_publisher/package.xml @@ -12,8 +12,8 @@ ament_cmake autoware_cmake - autoware_auto_mapping_msgs autoware_auto_perception_msgs + autoware_map_msgs geometry_msgs lanelet2_extension rclcpp diff --git a/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp b/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp index 6076d3fa32f26..6972a656b03ae 100644 --- a/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp +++ b/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp @@ -26,7 +26,7 @@ TrafficLightRecognitionMarkerPublisher::TrafficLightRecognitionMarkerPublisher( { using std::placeholders::_1; - sub_map_ptr_ = this->create_subscription( + sub_map_ptr_ = this->create_subscription( "~/input/lanelet2_map", rclcpp::QoS{1}.transient_local(), std::bind(&TrafficLightRecognitionMarkerPublisher::onMap, this, _1)); sub_tlr_ptr_ = this->create_subscription( @@ -36,7 +36,7 @@ TrafficLightRecognitionMarkerPublisher::TrafficLightRecognitionMarkerPublisher( this->create_publisher("~/output/marker", rclcpp::QoS{1}); } -void TrafficLightRecognitionMarkerPublisher::onMap(const HADMapBin::ConstSharedPtr msg_ptr) +void TrafficLightRecognitionMarkerPublisher::onMap(const LaneletMapBin::ConstSharedPtr msg_ptr) { is_map_ready_ = false; lanelet::LaneletMapPtr viz_lanelet_map(new lanelet::LaneletMap); diff --git a/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp b/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp index de9aea14b7e5a..25b5656a38817 100644 --- a/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp +++ b/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp @@ -21,8 +21,8 @@ #include #include -#include #include +#include #include #include @@ -32,7 +32,7 @@ class TrafficLightRecognitionMarkerPublisher : public rclcpp::Node { public: - using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; using TrafficSignalArray = autoware_auto_perception_msgs::msg::TrafficSignalArray; using TrafficLight = autoware_auto_perception_msgs::msg::TrafficLight; using MarkerArray = visualization_msgs::msg::MarkerArray; @@ -41,12 +41,12 @@ class TrafficLightRecognitionMarkerPublisher : public rclcpp::Node explicit TrafficLightRecognitionMarkerPublisher(const rclcpp::NodeOptions & options); private: - rclcpp::Subscription::SharedPtr sub_map_ptr_; + rclcpp::Subscription::SharedPtr sub_map_ptr_; rclcpp::Subscription::SharedPtr sub_tlr_ptr_; rclcpp::Publisher::SharedPtr pub_marker_ptr_; - void onMap(const HADMapBin::ConstSharedPtr msg_ptr); + void onMap(const LaneletMapBin::ConstSharedPtr msg_ptr); void onTrafficSignalArray(const TrafficSignalArray::ConstSharedPtr msg_ptr); visualization_msgs::msg::Marker getTrafficLightMarker( const Pose & tl_pose, const uint8_t tl_color, const uint8_t tl_shape); diff --git a/control/lane_departure_checker/README.md b/control/lane_departure_checker/README.md index 67b770aefb3d2..8eb0a11f6b09b 100644 --- a/control/lane_departure_checker/README.md +++ b/control/lane_departure_checker/README.md @@ -49,7 +49,7 @@ This package includes the following features: ### Input - /localization/kinematic_state [`nav_msgs::msg::Odometry`] -- /map/vector_map [`autoware_auto_mapping_msgs::msg::HADMapBin`] +- /map/vector_map [`autoware_map_msgs::msg::LaneletMapBin`] - /planning/mission_planning/route [`autoware_planning_msgs::msg::LaneletRoute`] - /planning/scenario_planning/trajectory [`autoware_auto_planning_msgs::msg::Trajectory`] - /control/trajectory_follower/predicted_trajectory [`autoware_auto_planning_msgs::msg::Trajectory`] diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp index dd05ab226f6b7..c840d65958cfd 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp +++ b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker_node.hpp @@ -22,8 +22,8 @@ #include #include -#include #include +#include #include #include #include @@ -42,7 +42,7 @@ namespace lane_departure_checker { -using autoware_auto_mapping_msgs::msg::HADMapBin; +using autoware_map_msgs::msg::LaneletMapBin; struct NodeParam { @@ -67,7 +67,7 @@ class LaneDepartureCheckerNode : public rclcpp::Node private: // Subscriber rclcpp::Subscription::SharedPtr sub_odom_; - rclcpp::Subscription::SharedPtr sub_lanelet_map_bin_; + rclcpp::Subscription::SharedPtr sub_lanelet_map_bin_; rclcpp::Subscription::SharedPtr sub_route_; rclcpp::Subscription::SharedPtr sub_reference_trajectory_; rclcpp::Subscription::SharedPtr sub_predicted_trajectory_; @@ -87,7 +87,7 @@ class LaneDepartureCheckerNode : public rclcpp::Node // Callback void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); - void onLaneletMapBin(const HADMapBin::ConstSharedPtr msg); + void onLaneletMapBin(const LaneletMapBin::ConstSharedPtr msg); void onRoute(const LaneletRoute::ConstSharedPtr msg); void onReferenceTrajectory(const Trajectory::ConstSharedPtr msg); void onPredictedTrajectory(const Trajectory::ConstSharedPtr msg); diff --git a/control/lane_departure_checker/package.xml b/control/lane_departure_checker/package.xml index 1059e86cadc6d..a35ffc8ee0639 100644 --- a/control/lane_departure_checker/package.xml +++ b/control/lane_departure_checker/package.xml @@ -11,8 +11,8 @@ ament_cmake_auto autoware_cmake - autoware_auto_mapping_msgs autoware_auto_planning_msgs + autoware_map_msgs autoware_planning_msgs boost diagnostic_updater diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index b40a0d0473135..528b25a424584 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -171,7 +171,7 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o // Subscriber sub_odom_ = this->create_subscription( "~/input/odometry", 1, std::bind(&LaneDepartureCheckerNode::onOdometry, this, _1)); - sub_lanelet_map_bin_ = this->create_subscription( + sub_lanelet_map_bin_ = this->create_subscription( "~/input/lanelet_map_bin", rclcpp::QoS{1}.transient_local(), std::bind(&LaneDepartureCheckerNode::onLaneletMapBin, this, _1)); sub_route_ = this->create_subscription( @@ -205,7 +205,7 @@ void LaneDepartureCheckerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSh current_odom_ = msg; } -void LaneDepartureCheckerNode::onLaneletMapBin(const HADMapBin::ConstSharedPtr msg) +void LaneDepartureCheckerNode::onLaneletMapBin(const LaneletMapBin::ConstSharedPtr msg) { lanelet_map_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_, &traffic_rules_, &routing_graph_); diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/README.md b/localization/landmark_based_localizer/ar_tag_based_localizer/README.md index f0c54d6393f7e..3173064d0b935 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/README.md +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/README.md @@ -15,7 +15,7 @@ The positions and orientations of the AR-Tags are assumed to be written in the L | Name | Type | Description | | :--------------------- | :---------------------------------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| `~/input/lanelet2_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | Data of lanelet2 | +| `~/input/lanelet2_map` | `autoware_map_msgs::msg::LaneletMapBin` | Data of lanelet2 | | `~/input/image` | `sensor_msgs::msg::Image` | Camera Image | | `~/input/camera_info` | `sensor_msgs::msg::CameraInfo` | Camera Info | | `~/input/ekf_pose` | `geometry_msgs::msg::PoseWithCovarianceStamped` | EKF Pose without IMU correction. It is used to validate detected AR tags by filtering out False Positives. Only if the EKF Pose and the AR tag-detected Pose are within a certain temporal and spatial range, the AR tag-detected Pose is considered valid and published. | diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index a66277c699a00..6b3dabc1f25d8 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -113,7 +113,7 @@ bool ArTagBasedLocalizer::setup() /* Subscribers */ - map_bin_sub_ = this->create_subscription( + map_bin_sub_ = this->create_subscription( "~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal), std::bind(&ArTagBasedLocalizer::map_bin_callback, this, std::placeholders::_1)); @@ -146,7 +146,7 @@ bool ArTagBasedLocalizer::setup() return true; } -void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg) +void ArTagBasedLocalizer::map_bin_callback(const LaneletMapBin::ConstSharedPtr & msg) { const std::vector landmarks = landmark_manager::parse_landmarks(msg, "apriltag_16h5", this->get_logger()); diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp index 889e76eb78ad2..d925af6b4be2f 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp @@ -66,7 +66,7 @@ class ArTagBasedLocalizer : public rclcpp::Node { - using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; using Image = sensor_msgs::msg::Image; using CameraInfo = sensor_msgs::msg::CameraInfo; using Pose = geometry_msgs::msg::Pose; @@ -81,7 +81,7 @@ class ArTagBasedLocalizer : public rclcpp::Node bool setup(); private: - void map_bin_callback(const HADMapBin::ConstSharedPtr & msg); + void map_bin_callback(const LaneletMapBin::ConstSharedPtr & msg); void image_callback(const Image::ConstSharedPtr & msg); void cam_info_callback(const CameraInfo & msg); void ekf_pose_callback(const PoseWithCovarianceStamped & msg); @@ -105,7 +105,7 @@ class ArTagBasedLocalizer : public rclcpp::Node std::unique_ptr it_; // Subscribers - rclcpp::Subscription::SharedPtr map_bin_sub_; + rclcpp::Subscription::SharedPtr map_bin_sub_; rclcpp::Subscription::SharedPtr image_sub_; rclcpp::Subscription::SharedPtr cam_info_sub_; rclcpp::Subscription::SharedPtr ekf_pose_sub_; diff --git a/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp index 9a22ee13f60ae..427df85e6d5e5 100644 --- a/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp +++ b/localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp @@ -17,7 +17,7 @@ #include -#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" +#include "autoware_map_msgs/msg/lanelet_map_bin.hpp" #include #include #include @@ -35,7 +35,7 @@ struct Landmark }; std::vector parse_landmarks( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr & msg, const std::string & target_subtype, const rclcpp::Logger & logger); visualization_msgs::msg::MarkerArray convert_landmarks_to_marker_array_msg( diff --git a/localization/landmark_based_localizer/landmark_manager/package.xml b/localization/landmark_based_localizer/landmark_manager/package.xml index 1a35ae6a338d1..494d3d9e01a9a 100644 --- a/localization/landmark_based_localizer/landmark_manager/package.xml +++ b/localization/landmark_based_localizer/landmark_manager/package.xml @@ -15,7 +15,7 @@ eigen - autoware_auto_mapping_msgs + autoware_map_msgs geometry_msgs lanelet2_extension rclcpp diff --git a/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp index 6d1698daf5eae..b642bbc24b0a5 100644 --- a/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp +++ b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp @@ -26,12 +26,12 @@ namespace landmark_manager { std::vector parse_landmarks( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr & msg, const std::string & target_subtype, const rclcpp::Logger & logger) { - RCLCPP_INFO_STREAM(logger, "msg->format_version: " << msg->format_version); - RCLCPP_INFO_STREAM(logger, "msg->map_format: " << msg->map_format); - RCLCPP_INFO_STREAM(logger, "msg->map_version: " << msg->map_version); + RCLCPP_INFO_STREAM(logger, "msg->format_version: " << msg->version_map_format); + RCLCPP_INFO_STREAM(logger, "msg->map_format: " << msg->name_map); + RCLCPP_INFO_STREAM(logger, "msg->map_version: " << msg->version_map); RCLCPP_INFO_STREAM(logger, "msg->data.size(): " << msg->data.size()); lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared()}; lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr); diff --git a/localization/yabloc/yabloc_common/README.md b/localization/yabloc/yabloc_common/README.md index 1160f1b314b99..52465eb5dc37b 100644 --- a/localization/yabloc/yabloc_common/README.md +++ b/localization/yabloc/yabloc_common/README.md @@ -15,10 +15,10 @@ It estimates the height and tilt of the ground from lanelet2. #### Input -| Name | Type | Description | -| ------------------ | -------------------------------------------- | ------------------- | -| `input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | -| `input/pose` | `geometry_msgs::msg::PoseStamped` | estimated self pose | +| Name | Type | Description | +| ------------------ | --------------------------------------- | ------------------- | +| `input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map | +| `input/pose` | `geometry_msgs::msg::PoseStamped` | estimated self pose | #### Output @@ -48,9 +48,9 @@ This node extracts the elements related to the road surface markings and yabloc #### Input -| Name | Type | Description | -| ------------------ | -------------------------------------------- | ----------- | -| `input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | +| Name | Type | Description | +| ------------------ | --------------------------------------- | ----------- | +| `input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map | #### Output diff --git a/localization/yabloc/yabloc_common/include/yabloc_common/ground_server/ground_server.hpp b/localization/yabloc/yabloc_common/include/yabloc_common/ground_server/ground_server.hpp index 154507f8195d9..d15449e90daf8 100644 --- a/localization/yabloc/yabloc_common/include/yabloc_common/ground_server/ground_server.hpp +++ b/localization/yabloc/yabloc_common/include/yabloc_common/ground_server/ground_server.hpp @@ -21,7 +21,7 @@ #include #include -#include +#include #include #include #include @@ -44,7 +44,7 @@ class GroundServer : public rclcpp::Node { public: using GroundPlane = common::GroundPlane; - using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; using Pose = geometry_msgs::msg::Pose; using PoseStamped = geometry_msgs::msg::PoseStamped; @@ -65,7 +65,7 @@ class GroundServer : public rclcpp::Node const int K; // Subscriber - rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_map_; rclcpp::Subscription::SharedPtr sub_pose_stamped_; rclcpp::Subscription::SharedPtr sub_initial_pose_; // Publisher @@ -86,7 +86,7 @@ class GroundServer : public rclcpp::Node std::vector last_indices_; // Callback - void on_map(const HADMapBin & msg); + void on_map(const LaneletMapBin & msg); void on_initial_pose(const PoseCovStamped & msg); void on_pose_stamped(const PoseStamped & msg); diff --git a/localization/yabloc/yabloc_common/include/yabloc_common/ll2_decomposer/ll2_decomposer.hpp b/localization/yabloc/yabloc_common/include/yabloc_common/ll2_decomposer/ll2_decomposer.hpp index f6e6de6b38fdd..950c54c32ef5c 100644 --- a/localization/yabloc/yabloc_common/include/yabloc_common/ll2_decomposer/ll2_decomposer.hpp +++ b/localization/yabloc/yabloc_common/include/yabloc_common/ll2_decomposer/ll2_decomposer.hpp @@ -17,7 +17,7 @@ #include -#include +#include #include #include #include @@ -35,7 +35,7 @@ class Ll2Decomposer : public rclcpp::Node { public: using Cloud2 = sensor_msgs::msg::PointCloud2; - using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; using Marker = visualization_msgs::msg::Marker; using MarkerArray = visualization_msgs::msg::MarkerArray; @@ -47,12 +47,12 @@ class Ll2Decomposer : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_bounding_box_; rclcpp::Publisher::SharedPtr pub_marker_; - rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_map_; std::set road_marking_labels_; std::set sign_board_labels_; std::set bounding_box_labels_; - void on_map(const HADMapBin & msg); + void on_map(const LaneletMapBin & msg); pcl::PointNormal to_point_normal( const lanelet::ConstPoint3d & from, const lanelet::ConstPoint3d & to) const; diff --git a/localization/yabloc/yabloc_common/package.xml b/localization/yabloc/yabloc_common/package.xml index d7e94ebefa24b..182c45b6ddeef 100644 --- a/localization/yabloc/yabloc_common/package.xml +++ b/localization/yabloc/yabloc_common/package.xml @@ -11,7 +11,7 @@ autoware_cmake rosidl_default_generators - autoware_auto_mapping_msgs + autoware_map_msgs cv_bridge geometry_msgs lanelet2_core diff --git a/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp b/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp index 749aa39318923..276eef32dc157 100644 --- a/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp +++ b/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp @@ -43,7 +43,7 @@ GroundServer::GroundServer() auto on_pose = std::bind(&GroundServer::on_pose_stamped, this, _1); auto on_map = std::bind(&GroundServer::on_map, this, _1); - sub_map_ = create_subscription("~/input/vector_map", map_qos, on_map); + sub_map_ = create_subscription("~/input/vector_map", map_qos, on_map); sub_pose_stamped_ = create_subscription("~/input/pose", 10, on_pose); pub_ground_height_ = create_publisher("~/output/height", 10); @@ -100,7 +100,7 @@ void GroundServer::on_pose_stamped(const PoseStamped & msg) } } -void GroundServer::on_map(const HADMapBin & msg) +void GroundServer::on_map(const LaneletMapBin & msg) { lanelet::LaneletMapPtr lanelet_map(new lanelet::LaneletMap); lanelet::utils::conversion::fromBinMsg(msg, lanelet_map); diff --git a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp b/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp index 5cf3e905e447d..91eb5540fe743 100644 --- a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp +++ b/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp @@ -38,7 +38,7 @@ Ll2Decomposer::Ll2Decomposer() : Node("ll2_to_image") // Subscriber auto cb_map = std::bind(&Ll2Decomposer::on_map, this, _1); - sub_map_ = create_subscription("~/input/vector_map", map_qos, cb_map); + sub_map_ = create_subscription("~/input/vector_map", map_qos, cb_map); auto load_lanelet2_labels = [this](const std::string & param_name, std::set & labels) -> void { @@ -102,7 +102,7 @@ pcl::PointCloud Ll2Decomposer::load_bounding_boxes( return cloud; } -void Ll2Decomposer::on_map(const HADMapBin & msg) +void Ll2Decomposer::on_map(const LaneletMapBin & msg) { RCLCPP_INFO_STREAM(get_logger(), "subscribed binary vector map"); lanelet::LaneletMapPtr lanelet_map(new lanelet::LaneletMap); diff --git a/localization/yabloc/yabloc_pose_initializer/README.md b/localization/yabloc/yabloc_pose_initializer/README.md index 907b79c1459ec..620c404a321d7 100644 --- a/localization/yabloc/yabloc_pose_initializer/README.md +++ b/localization/yabloc/yabloc_pose_initializer/README.md @@ -45,11 +45,11 @@ Converted model URL #### Input -| Name | Type | Description | -| ------------------- | -------------------------------------------- | ------------------------ | -| `input/camera_info` | `sensor_msgs::msg::CameraInfo` | undistorted camera info | -| `input/image_raw` | `sensor_msgs::msg::Image` | undistorted camera image | -| `input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | +| Name | Type | Description | +| ------------------- | --------------------------------------- | ------------------------ | +| `input/camera_info` | `sensor_msgs::msg::CameraInfo` | undistorted camera info | +| `input/image_raw` | `sensor_msgs::msg::Image` | undistorted camera image | +| `input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map | #### Output diff --git a/localization/yabloc/yabloc_pose_initializer/include/yabloc_pose_initializer/camera/camera_pose_initializer.hpp b/localization/yabloc/yabloc_pose_initializer/include/yabloc_pose_initializer/camera/camera_pose_initializer.hpp index 917a6ecaaf291..979d1b370699e 100644 --- a/localization/yabloc/yabloc_pose_initializer/include/yabloc_pose_initializer/camera/camera_pose_initializer.hpp +++ b/localization/yabloc/yabloc_pose_initializer/include/yabloc_pose_initializer/camera/camera_pose_initializer.hpp @@ -23,7 +23,7 @@ #include #include -#include +#include #include #include #include @@ -40,7 +40,7 @@ class CameraPoseInitializer : public rclcpp::Node using PoseCovStamped = geometry_msgs::msg::PoseWithCovarianceStamped; using PointCloud2 = sensor_msgs::msg::PointCloud2; using Image = sensor_msgs::msg::Image; - using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; using RequestPoseAlignment = tier4_localization_msgs::srv::PoseWithCovarianceStamped; CameraPoseInitializer(); @@ -52,7 +52,7 @@ class CameraPoseInitializer : public rclcpp::Node std::unique_ptr projector_module_{nullptr}; rclcpp::Subscription::SharedPtr sub_initialpose_; - rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_map_; rclcpp::Subscription::SharedPtr sub_image_; rclcpp::Service::SharedPtr align_server_; @@ -63,7 +63,7 @@ class CameraPoseInitializer : public rclcpp::Node std::unique_ptr semantic_segmentation_{nullptr}; - void on_map(const HADMapBin & msg); + void on_map(const LaneletMapBin & msg); void on_service( const RequestPoseAlignment::Request::SharedPtr, RequestPoseAlignment::Response::SharedPtr request); diff --git a/localization/yabloc/yabloc_pose_initializer/package.xml b/localization/yabloc/yabloc_pose_initializer/package.xml index 4e3ca1c1e61d1..e6d5ceb634be3 100644 --- a/localization/yabloc/yabloc_pose_initializer/package.xml +++ b/localization/yabloc/yabloc_pose_initializer/package.xml @@ -11,7 +11,7 @@ autoware_cmake rosidl_default_generators - autoware_auto_mapping_msgs + autoware_map_msgs geometry_msgs lanelet2_extension rclcpp diff --git a/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp index 19d3c8d88f260..083e7dd5bcd43 100644 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp +++ b/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp @@ -40,7 +40,7 @@ CameraPoseInitializer::CameraPoseInitializer() // Subscriber auto on_map = std::bind(&CameraPoseInitializer::on_map, this, _1); auto on_image = [this](Image::ConstSharedPtr msg) -> void { latest_image_msg_ = msg; }; - sub_map_ = create_subscription("~/input/vector_map", map_qos, on_map); + sub_map_ = create_subscription("~/input/vector_map", map_qos, on_map); sub_image_ = create_subscription("~/input/image_raw", 10, on_image); // Server @@ -164,7 +164,7 @@ std::optional CameraPoseInitializer::estimate_pose( return angles_rad.at(max_index); } -void CameraPoseInitializer::on_map(const HADMapBin & msg) +void CameraPoseInitializer::on_map(const LaneletMapBin & msg) { lanelet::LaneletMapPtr lanelet_map(new lanelet::LaneletMap); lanelet::utils::conversion::fromBinMsg(msg, lanelet_map); diff --git a/map/map_loader/README.md b/map/map_loader/README.md index 65d9594cb7415..82f7e8bbb2c58 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -141,7 +141,7 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co ### Feature -lanelet2_map_loader loads Lanelet2 file and publishes the map data as autoware_auto_mapping_msgs/HADMapBin message. +lanelet2_map_loader loads Lanelet2 file and publishes the map data as autoware_map_msgs/LaneletMapBin message. The node projects lan/lon coordinates into arbitrary coordinates defined in `/map/map_projector_info` from `map_projection_loader`. Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_map_msgs/msg/MapProjectorInfo.msg) for supported projector types. @@ -155,7 +155,7 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie ### Published Topics -- ~output/lanelet2_map (autoware_auto_mapping_msgs/HADMapBin) : Binary data of loaded Lanelet2 Map +- ~output/lanelet2_map (autoware_map_msgs/LaneletMapBin) : Binary data of loaded Lanelet2 Map ### Parameters @@ -170,7 +170,7 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie ### Feature -lanelet2_map_visualization visualizes autoware_auto_mapping_msgs/HADMapBin messages into visualization_msgs/MarkerArray. +lanelet2_map_visualization visualizes autoware_map_msgs/LaneletMapBin messages into visualization_msgs/MarkerArray. ### How to Run @@ -178,7 +178,7 @@ lanelet2_map_visualization visualizes autoware_auto_mapping_msgs/HADMapBin messa ### Subscribed Topics -- ~input/lanelet2_map (autoware_auto_mapping_msgs/HADMapBin) : binary data of Lanelet2 Map +- ~input/lanelet2_map (autoware_map_msgs/LaneletMapBin) : binary data of Lanelet2 Map ### Published Topics diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp index 0adc7612e9f61..4e85ddec056c1 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp +++ b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -27,7 +27,7 @@ #include #include -using autoware_auto_mapping_msgs::msg::HADMapBin; +using autoware_map_msgs::msg::LaneletMapBin; using tier4_map_msgs::msg::MapProjectorInfo; class Lanelet2MapLoaderNode : public rclcpp::Node @@ -38,7 +38,7 @@ class Lanelet2MapLoaderNode : public rclcpp::Node static lanelet::LaneletMapPtr load_map( const std::string & lanelet2_filename, const tier4_map_msgs::msg::MapProjectorInfo & projector_info); - static HADMapBin create_map_bin_msg( + static LaneletMapBin create_map_bin_msg( const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now); @@ -48,7 +48,7 @@ class Lanelet2MapLoaderNode : public rclcpp::Node void on_map_projector_info(const MapProjectorInfo::Message::ConstSharedPtr msg); component_interface_utils::Subscription::SharedPtr sub_map_projector_info_; - rclcpp::Publisher::SharedPtr pub_map_bin_; + rclcpp::Publisher::SharedPtr pub_map_bin_; }; #endif // MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ diff --git a/map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp b/map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp index e5a5fe3e3a6fa..cb640e4dc83d5 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp +++ b/map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp @@ -17,7 +17,7 @@ #include -#include +#include #include #include @@ -29,12 +29,12 @@ class Lanelet2MapVisualizationNode : public rclcpp::Node explicit Lanelet2MapVisualizationNode(const rclcpp::NodeOptions & options); private: - rclcpp::Subscription::SharedPtr sub_map_bin_; + rclcpp::Subscription::SharedPtr sub_map_bin_; rclcpp::Publisher::SharedPtr pub_marker_; bool viz_lanelets_centerline_; - void onMapBin(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg); + void onMapBin(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg); }; #endif // MAP_LOADER__LANELET2_MAP_VISUALIZATION_NODE_HPP_ diff --git a/map/map_loader/package.xml b/map/map_loader/package.xml index 5230d4bd03214..77722b77d8d1d 100644 --- a/map/map_loader/package.xml +++ b/map/map_loader/package.xml @@ -14,7 +14,6 @@ ament_cmake_auto autoware_cmake - autoware_auto_mapping_msgs autoware_map_msgs component_interface_specs component_interface_utils diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index 259c168edcc5c..3aaaf63518813 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -83,7 +83,7 @@ void Lanelet2MapLoaderNode::on_map_projector_info( // create publisher and publish pub_map_bin_ = - create_publisher("output/lanelet2_map", rclcpp::QoS{1}.transient_local()); + create_publisher("output/lanelet2_map", rclcpp::QoS{1}.transient_local()); pub_map_bin_->publish(map_bin_msg); } @@ -132,18 +132,18 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( return nullptr; } -HADMapBin Lanelet2MapLoaderNode::create_map_bin_msg( +LaneletMapBin Lanelet2MapLoaderNode::create_map_bin_msg( const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now) { std::string format_version{}, map_version{}; lanelet::io_handlers::AutowareOsmParser::parseVersions( lanelet2_filename, &format_version, &map_version); - HADMapBin map_bin_msg; + LaneletMapBin map_bin_msg; map_bin_msg.header.stamp = now; map_bin_msg.header.frame_id = "map"; - map_bin_msg.format_version = format_version; - map_bin_msg.map_version = map_version; + map_bin_msg.version_map_format = format_version; + map_bin_msg.version_map = map_version; lanelet::utils::conversion::toBinMsg(map, &map_bin_msg); return map_bin_msg; diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp index 082dc95d6500a..a5d10ec60a8c7 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp @@ -39,7 +39,7 @@ #include #include -#include +#include #include #include @@ -73,7 +73,7 @@ Lanelet2MapVisualizationNode::Lanelet2MapVisualizationNode(const rclcpp::NodeOpt viz_lanelets_centerline_ = this->declare_parameter("viz_lanelets_centerline", true); - sub_map_bin_ = this->create_subscription( + sub_map_bin_ = this->create_subscription( "input/lanelet2_map", rclcpp::QoS{1}.transient_local(), std::bind(&Lanelet2MapVisualizationNode::onMapBin, this, _1)); @@ -82,7 +82,7 @@ Lanelet2MapVisualizationNode::Lanelet2MapVisualizationNode(const rclcpp::NodeOpt } void Lanelet2MapVisualizationNode::onMapBin( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg) { lanelet::LaneletMapPtr viz_lanelet_map(new lanelet::LaneletMap); diff --git a/map/map_tf_generator/Readme.md b/map/map_tf_generator/Readme.md index 1b858ec12c2c2..a8886a314f7a2 100644 --- a/map/map_tf_generator/Readme.md +++ b/map/map_tf_generator/Readme.md @@ -25,9 +25,9 @@ The following are the supported methods to calculate the position of the `viewer #### vector_map_tf_generator -| Name | Type | Description | -| ----------------- | -------------------------------------------- | ------------------------------------------------------------- | -| `/map/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | Subscribe vector map to calculate position of `viewer` frames | +| Name | Type | Description | +| ----------------- | --------------------------------------- | ------------------------------------------------------------- | +| `/map/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | Subscribe vector map to calculate position of `viewer` frames | ### Output diff --git a/map/map_tf_generator/src/vector_map_tf_generator_node.cpp b/map/map_tf_generator/src/vector_map_tf_generator_node.cpp index 055d71cfb2b35..f335a80adab1f 100644 --- a/map/map_tf_generator/src/vector_map_tf_generator_node.cpp +++ b/map/map_tf_generator/src/vector_map_tf_generator_node.cpp @@ -15,7 +15,7 @@ #include #include -#include +#include #include #include @@ -34,7 +34,7 @@ class VectorMapTFGeneratorNode : public rclcpp::Node map_frame_ = declare_parameter("map_frame", "map"); viewer_frame_ = declare_parameter("viewer_frame", "viewer"); - sub_ = create_subscription( + sub_ = create_subscription( "vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&VectorMapTFGeneratorNode::onVectorMap, this, std::placeholders::_1)); @@ -44,12 +44,12 @@ class VectorMapTFGeneratorNode : public rclcpp::Node private: std::string map_frame_; std::string viewer_frame_; - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; std::shared_ptr static_broadcaster_; std::shared_ptr lanelet_map_ptr_; - void onVectorMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg) + void onVectorMap(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg) { lanelet_map_ptr_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr_); diff --git a/perception/crosswalk_traffic_light_estimator/README.md b/perception/crosswalk_traffic_light_estimator/README.md index 73c7151997c54..51166b1e792ae 100644 --- a/perception/crosswalk_traffic_light_estimator/README.md +++ b/perception/crosswalk_traffic_light_estimator/README.md @@ -10,7 +10,7 @@ | Name | Type | Description | | ------------------------------------ | ------------------------------------------------ | ------------------ | -| `~/input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | +| `~/input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map | | `~/input/route` | `autoware_planning_msgs::msg::LaneletRoute` | route | | `~/input/classified/traffic_signals` | `tier4_perception_msgs::msg::TrafficSignalArray` | classified signals | diff --git a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp index e38b747a6ce67..5b3ef38821ca7 100644 --- a/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp +++ b/perception/crosswalk_traffic_light_estimator/include/crosswalk_traffic_light_estimator/node.hpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include #include @@ -42,7 +42,7 @@ namespace traffic_light { -using autoware_auto_mapping_msgs::msg::HADMapBin; +using autoware_map_msgs::msg::LaneletMapBin; using autoware_planning_msgs::msg::LaneletRoute; using tier4_autoware_utils::DebugPublisher; using tier4_autoware_utils::StopWatch; @@ -59,7 +59,7 @@ class CrosswalkTrafficLightEstimatorNode : public rclcpp::Node explicit CrosswalkTrafficLightEstimatorNode(const rclcpp::NodeOptions & options); private: - rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_map_; rclcpp::Subscription::SharedPtr sub_route_; rclcpp::Subscription::SharedPtr sub_traffic_light_array_; rclcpp::Publisher::SharedPtr pub_traffic_light_array_; @@ -71,7 +71,7 @@ class CrosswalkTrafficLightEstimatorNode : public rclcpp::Node lanelet::ConstLanelets conflicting_crosswalks_; - void onMap(const HADMapBin::ConstSharedPtr msg); + void onMap(const LaneletMapBin::ConstSharedPtr msg); void onRoute(const LaneletRoute::ConstSharedPtr msg); void onTrafficLightArray(const TrafficSignalArray::ConstSharedPtr msg); diff --git a/perception/crosswalk_traffic_light_estimator/package.xml b/perception/crosswalk_traffic_light_estimator/package.xml index bec5b666683c4..b2fd1578d54ac 100644 --- a/perception/crosswalk_traffic_light_estimator/package.xml +++ b/perception/crosswalk_traffic_light_estimator/package.xml @@ -12,8 +12,8 @@ ament_cmake_auto autoware_cmake - autoware_auto_mapping_msgs autoware_auto_planning_msgs + autoware_map_msgs autoware_perception_msgs autoware_planning_msgs lanelet2_extension diff --git a/perception/crosswalk_traffic_light_estimator/src/node.cpp b/perception/crosswalk_traffic_light_estimator/src/node.cpp index 870b8bc7c13f5..0a43a4c40f47b 100644 --- a/perception/crosswalk_traffic_light_estimator/src/node.cpp +++ b/perception/crosswalk_traffic_light_estimator/src/node.cpp @@ -85,7 +85,7 @@ CrosswalkTrafficLightEstimatorNode::CrosswalkTrafficLightEstimatorNode( use_last_detect_color_ = declare_parameter("use_last_detect_color"); last_detect_color_hold_time_ = declare_parameter("last_detect_color_hold_time"); - sub_map_ = create_subscription( + sub_map_ = create_subscription( "~/input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&CrosswalkTrafficLightEstimatorNode::onMap, this, _1)); sub_route_ = create_subscription( @@ -100,7 +100,7 @@ CrosswalkTrafficLightEstimatorNode::CrosswalkTrafficLightEstimatorNode( pub_processing_time_ = std::make_shared(this, "~/debug"); } -void CrosswalkTrafficLightEstimatorNode::onMap(const HADMapBin::ConstSharedPtr msg) +void CrosswalkTrafficLightEstimatorNode::onMap(const LaneletMapBin::ConstSharedPtr msg) { RCLCPP_INFO(get_logger(), "[CrosswalkTrafficLightEstimatorNode]: Start loading lanelet"); lanelet_map_ptr_ = std::make_shared(); diff --git a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp b/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp index ae6162542a1c3..3a612b5d27973 100644 --- a/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp @@ -20,8 +20,8 @@ #include #include -#include #include +#include #include #include @@ -43,10 +43,10 @@ class ObjectLaneletFilterNode : public rclcpp::Node private: void objectCallback(const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr); - void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr); + void mapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr); rclcpp::Publisher::SharedPtr object_pub_; - rclcpp::Subscription::SharedPtr map_sub_; + rclcpp::Subscription::SharedPtr map_sub_; rclcpp::Subscription::SharedPtr object_sub_; lanelet::LaneletMapPtr lanelet_map_ptr_; diff --git a/perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp b/perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp index b9384e0f70379..2a10883527293 100644 --- a/perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_filter/object_position_filter.hpp @@ -20,8 +20,8 @@ #include #include -#include #include +#include #include #include diff --git a/perception/detected_object_validation/object-lanelet-filter.md b/perception/detected_object_validation/object-lanelet-filter.md index eebd8ede79270..19ecfc84aa62d 100644 --- a/perception/detected_object_validation/object-lanelet-filter.md +++ b/perception/detected_object_validation/object-lanelet-filter.md @@ -13,7 +13,7 @@ The objects only inside of the vector map will be published. | Name | Type | Description | | ------------------ | ----------------------------------------------------- | ---------------------- | -| `input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | +| `input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map | | `input/object` | `autoware_auto_perception_msgs::msg::DetectedObjects` | input detected objects | ### Output diff --git a/perception/detected_object_validation/package.xml b/perception/detected_object_validation/package.xml index e19b2b1c399b2..01b478ded2bf0 100644 --- a/perception/detected_object_validation/package.xml +++ b/perception/detected_object_validation/package.xml @@ -14,8 +14,8 @@ libopencv-dev - autoware_auto_mapping_msgs autoware_auto_perception_msgs + autoware_map_msgs geometry_msgs lanelet2_extension message_filters diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp index f9b208cca02bc..e741d6b5fec1d 100644 --- a/perception/detected_object_validation/src/object_lanelet_filter.cpp +++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp @@ -45,7 +45,7 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod filter_target_.PEDESTRIAN = declare_parameter("filter_target_label.PEDESTRIAN", false); // Set publisher/subscriber - map_sub_ = this->create_subscription( + map_sub_ = this->create_subscription( "input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&ObjectLaneletFilterNode::mapCallback, this, _1)); object_sub_ = this->create_subscription( @@ -55,7 +55,7 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod } void ObjectLaneletFilterNode::mapCallback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr map_msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr map_msg) { lanelet_frame_id_ = map_msg->header.frame_id; lanelet_map_ptr_ = std::make_shared(); diff --git a/perception/elevation_map_loader/README.md b/perception/elevation_map_loader/README.md index 0fa644cbb304d..6920ed927a18a 100644 --- a/perception/elevation_map_loader/README.md +++ b/perception/elevation_map_loader/README.md @@ -23,7 +23,7 @@ Cells with No elevation value can be inpainted using the values of neighboring c | Name | Type | Description | | ------------------------------- | ----------------------------------------------- | ------------------------------------------ | | `input/pointcloud_map` | `sensor_msgs::msg::PointCloud2` | The point cloud map | -| `input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | (Optional) The binary data of lanelet2 map | +| `input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | (Optional) The binary data of lanelet2 map | | `input/pointcloud_map_metadata` | `autoware_map_msgs::msg::PointCloudMapMetaData` | (Optional) The metadata of point cloud map | ### Output diff --git a/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp b/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp index 7c0609ee1cdce..88f7bf4a9c2a9 100644 --- a/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp +++ b/perception/elevation_map_loader/include/elevation_map_loader/elevation_map_loader_node.hpp @@ -23,7 +23,7 @@ #include #include "tier4_external_api_msgs/msg/map_hash.hpp" -#include +#include #include #include #include @@ -64,7 +64,7 @@ class ElevationMapLoaderNode : public rclcpp::Node private: rclcpp::Subscription::SharedPtr sub_pointcloud_map_; - rclcpp::Subscription::SharedPtr sub_vector_map_; + rclcpp::Subscription::SharedPtr sub_vector_map_; rclcpp::Subscription::SharedPtr sub_map_hash_; rclcpp::Subscription::SharedPtr sub_pointcloud_metadata_; @@ -76,7 +76,7 @@ class ElevationMapLoaderNode : public rclcpp::Node void onPointcloudMap(const sensor_msgs::msg::PointCloud2::ConstSharedPtr pointcloud_map); void onMapHash(const tier4_external_api_msgs::msg::MapHash::ConstSharedPtr map_hash); void timerCallback(); - void onVectorMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr vector_map); + void onVectorMap(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr vector_map); void onPointCloudMapMetaData( const autoware_map_msgs::msg::PointCloudMapMetaData pointcloud_map_metadata); void receiveMap(); diff --git a/perception/elevation_map_loader/package.xml b/perception/elevation_map_loader/package.xml index 6e271b8528c47..d10c14b1701e7 100644 --- a/perception/elevation_map_loader/package.xml +++ b/perception/elevation_map_loader/package.xml @@ -11,7 +11,6 @@ ament_cmake_auto autoware_cmake - autoware_auto_mapping_msgs autoware_map_msgs grid_map_cv grid_map_pcl diff --git a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp index 425af519a80ea..afb85fc9318de 100644 --- a/perception/elevation_map_loader/src/elevation_map_loader_node.cpp +++ b/perception/elevation_map_loader/src/elevation_map_loader_node.cpp @@ -93,7 +93,7 @@ ElevationMapLoaderNode::ElevationMapLoaderNode(const rclcpp::NodeOptions & optio sub_map_hash_ = create_subscription( "/api/autoware/get/map/info/hash", durable_qos, std::bind(&ElevationMapLoaderNode::onMapHash, this, _1)); - sub_vector_map_ = this->create_subscription( + sub_vector_map_ = this->create_subscription( "input/vector_map", durable_qos, std::bind(&ElevationMapLoaderNode::onVectorMap, this, _1)); if (use_sequential_load) { { @@ -237,7 +237,7 @@ void ElevationMapLoaderNode::onPointCloudMapMetaData( } void ElevationMapLoaderNode::onVectorMap( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr vector_map) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr vector_map) { RCLCPP_INFO(this->get_logger(), "subscribe vector_map"); data_manager_.lanelet_map_ptr_ = std::make_shared(); diff --git a/perception/map_based_prediction/README.md b/perception/map_based_prediction/README.md index 6d3d7f5e035a9..a5eb5fa295e2c 100644 --- a/perception/map_based_prediction/README.md +++ b/perception/map_based_prediction/README.md @@ -154,7 +154,7 @@ If the target object is inside the road or crosswalk, this module outputs one or | Name | Type | Description | | -------------------------------------------------- | ---------------------------------------------------- | ---------------------------------------- | | `~/perception/object_recognition/tracking/objects` | `autoware_auto_perception_msgs::msg::TrackedObjects` | tracking objects without predicted path. | -| `~/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | binary data of Lanelet2 Map. | +| `~/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | binary data of Lanelet2 Map. | ### Output diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 01f39057aef36..d6ed0aa6c65b7 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -21,9 +21,9 @@ #include #include -#include #include #include +#include #include #include #include @@ -90,7 +90,6 @@ struct PredictedRefPath using LaneletsData = std::vector; using ManeuverProbability = std::unordered_map; -using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_perception_msgs::msg::ObjectClassification; using autoware_auto_perception_msgs::msg::PredictedObject; using autoware_auto_perception_msgs::msg::PredictedObjectKinematics; @@ -99,6 +98,7 @@ using autoware_auto_perception_msgs::msg::PredictedPath; using autoware_auto_perception_msgs::msg::TrackedObject; using autoware_auto_perception_msgs::msg::TrackedObjectKinematics; using autoware_auto_perception_msgs::msg::TrackedObjects; +using autoware_map_msgs::msg::LaneletMapBin; using tier4_autoware_utils::StopWatch; using tier4_debug_msgs::msg::StringStamped; @@ -113,7 +113,7 @@ class MapBasedPredictionNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_debug_markers_; rclcpp::Publisher::SharedPtr pub_calculation_time_; rclcpp::Subscription::SharedPtr sub_objects_; - rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_map_; // Object History std::unordered_map> objects_history_; @@ -163,7 +163,7 @@ class MapBasedPredictionNode : public rclcpp::Node StopWatch stop_watch_; // Member Functions - void mapCallback(const HADMapBin::ConstSharedPtr msg); + void mapCallback(const LaneletMapBin::ConstSharedPtr msg); void objectsCallback(const TrackedObjects::ConstSharedPtr in_objects); bool doesPathCrossAnyFence(const PredictedPath & predicted_path); diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 2ceb22fd6e7b9..8f555453b806a 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -774,7 +774,7 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ sub_objects_ = this->create_subscription( "~/input/objects", 1, std::bind(&MapBasedPredictionNode::objectsCallback, this, std::placeholders::_1)); - sub_map_ = this->create_subscription( + sub_map_ = this->create_subscription( "/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&MapBasedPredictionNode::mapCallback, this, std::placeholders::_1)); @@ -807,7 +807,7 @@ PredictedObject MapBasedPredictionNode::convertToPredictedObject( return predicted_object; } -void MapBasedPredictionNode::mapCallback(const HADMapBin::ConstSharedPtr msg) +void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg) { RCLCPP_INFO(get_logger(), "[Map Based Prediction]: Start loading lanelet"); lanelet_map_ptr_ = std::make_shared(); diff --git a/perception/radar_object_tracker/include/radar_object_tracker/radar_object_tracker_node/radar_object_tracker_node.hpp b/perception/radar_object_tracker/include/radar_object_tracker/radar_object_tracker_node/radar_object_tracker_node.hpp index 9a3fdf602a3ca..40384ebdecee1 100644 --- a/perception/radar_object_tracker/include/radar_object_tracker/radar_object_tracker_node/radar_object_tracker_node.hpp +++ b/perception/radar_object_tracker/include/radar_object_tracker/radar_object_tracker_node/radar_object_tracker_node.hpp @@ -51,11 +51,11 @@ #include #include -using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_perception_msgs::msg::DetectedObject; using autoware_auto_perception_msgs::msg::DetectedObjects; using autoware_auto_perception_msgs::msg::TrackedObject; using autoware_auto_perception_msgs::msg::TrackedObjects; +using autoware_map_msgs::msg::LaneletMapBin; class RadarObjectTrackerNode : public rclcpp::Node { @@ -68,8 +68,8 @@ class RadarObjectTrackerNode : public rclcpp::Node tracked_objects_pub_; rclcpp::Subscription::SharedPtr detected_object_sub_; - rclcpp::TimerBase::SharedPtr publish_timer_; // publish timer - rclcpp::Subscription::SharedPtr sub_map_; // map subscriber + rclcpp::TimerBase::SharedPtr publish_timer_; // publish timer + rclcpp::Subscription::SharedPtr sub_map_; // map subscriber tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; @@ -81,7 +81,7 @@ class RadarObjectTrackerNode : public rclcpp::Node void onMeasurement( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg); void onTimer(); - void onMap(const HADMapBin::ConstSharedPtr map_msg); + void onMap(const LaneletMapBin::ConstSharedPtr map_msg); std::string world_frame_id_; // tracking frame std::string tracker_config_directory_; diff --git a/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp b/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp index 6d801302ab6c5..220f3af0bec41 100644 --- a/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp +++ b/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp @@ -200,7 +200,7 @@ RadarObjectTrackerNode::RadarObjectTrackerNode(const rclcpp::NodeOptions & node_ std::bind(&RadarObjectTrackerNode::onMeasurement, this, std::placeholders::_1)); tracked_objects_pub_ = create_publisher("output", rclcpp::QoS{1}); - sub_map_ = this->create_subscription( + sub_map_ = this->create_subscription( "/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&RadarObjectTrackerNode::onMap, this, std::placeholders::_1)); @@ -271,7 +271,7 @@ RadarObjectTrackerNode::RadarObjectTrackerNode(const rclcpp::NodeOptions & node_ } // load map information to node parameter -void RadarObjectTrackerNode::onMap(const HADMapBin::ConstSharedPtr msg) +void RadarObjectTrackerNode::onMap(const LaneletMapBin::ConstSharedPtr msg) { RCLCPP_INFO(get_logger(), "[Radar Object Tracker]: Start loading lanelet"); lanelet_map_ptr_ = std::make_shared(); diff --git a/perception/traffic_light_arbiter/README.md b/perception/traffic_light_arbiter/README.md index 952119020c215..e9f4901a51e90 100644 --- a/perception/traffic_light_arbiter/README.md +++ b/perception/traffic_light_arbiter/README.md @@ -14,7 +14,7 @@ A node that merges traffic light/signal state from image recognition and externa | Name | Type | Description | | -------------------------------- | ------------------------------------------------- | -------------------------------------------------------- | -| ~/sub/vector_map | autoware_auto_mapping_msgs::msg::HADMapBin | The vector map to get valid traffic signal ids. | +| ~/sub/vector_map | autoware_map_msgs::msg::LaneletMapBin | The vector map to get valid traffic signal ids. | | ~/sub/perception_traffic_signals | autoware_perception_msgs::msg::TrafficSignalArray | The traffic signals from the image recognition pipeline. | | ~/sub/external_traffic_signals | autoware_perception_msgs::msg::TrafficSignalArray | The traffic signals from an external system. | diff --git a/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp b/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp index 485ce84c5fea6..96083f5d724c4 100644 --- a/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp +++ b/perception/traffic_light_arbiter/include/traffic_light_arbiter/traffic_light_arbiter.hpp @@ -17,7 +17,7 @@ #include -#include +#include #include #include @@ -32,7 +32,7 @@ class TrafficLightArbiter : public rclcpp::Node private: using Element = autoware_perception_msgs::msg::TrafficSignalElement; - using LaneletMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; using TrafficSignalArray = autoware_perception_msgs::msg::TrafficSignalArray; using TrafficSignal = autoware_perception_msgs::msg::TrafficSignal; diff --git a/perception/traffic_light_arbiter/package.xml b/perception/traffic_light_arbiter/package.xml index a95df132de3bd..f5e396ba4c0fb 100644 --- a/perception/traffic_light_arbiter/package.xml +++ b/perception/traffic_light_arbiter/package.xml @@ -11,7 +11,7 @@ ament_cmake_auto autoware_cmake - autoware_auto_mapping_msgs + autoware_map_msgs autoware_perception_msgs lanelet2_core lanelet2_extension diff --git a/perception/traffic_light_map_based_detector/README.md b/perception/traffic_light_map_based_detector/README.md index e03a4c6dd8f69..5f1cc3a1d44f6 100644 --- a/perception/traffic_light_map_based_detector/README.md +++ b/perception/traffic_light_map_based_detector/README.md @@ -15,7 +15,7 @@ If the node receives no route information, it looks at a radius of 200 meters an | Name | Type | Description | | -------------------- | ------------------------------------- | ----------------------- | -| `~input/vector_map` | autoware_auto_mapping_msgs::HADMapBin | vector map | +| `~input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | | `~input/camera_info` | sensor_msgs::CameraInfo | target camera parameter | | `~input/route` | autoware_planning_msgs::LaneletRoute | optional: route | diff --git a/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp b/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp index e46431a7b199e..21a12494da5f3 100644 --- a/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp +++ b/perception/traffic_light_map_based_detector/include/traffic_light_map_based_detector/node.hpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include #include #include @@ -70,7 +70,7 @@ class MapBasedDetector : public rclcpp::Node }; private: - rclcpp::Subscription::SharedPtr map_sub_; + rclcpp::Subscription::SharedPtr map_sub_; rclcpp::Subscription::SharedPtr camera_info_sub_; rclcpp::Subscription::SharedPtr route_sub_; /** @@ -114,7 +114,7 @@ class MapBasedDetector : public rclcpp::Node * * @param input_msg */ - void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg); + void mapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_msg); /** * @brief callback function for the camera info message. The main process function of the node * diff --git a/perception/traffic_light_map_based_detector/package.xml b/perception/traffic_light_map_based_detector/package.xml index c2d53869fa3d5..8ff6f6061d208 100644 --- a/perception/traffic_light_map_based_detector/package.xml +++ b/perception/traffic_light_map_based_detector/package.xml @@ -11,8 +11,8 @@ autoware_cmake - autoware_auto_mapping_msgs autoware_auto_planning_msgs + autoware_map_msgs autoware_planning_msgs geometry_msgs image_geometry diff --git a/perception/traffic_light_map_based_detector/src/node.cpp b/perception/traffic_light_map_based_detector/src/node.cpp index f0a5d7b7b1fde..e13f4a38fd010 100644 --- a/perception/traffic_light_map_based_detector/src/node.cpp +++ b/perception/traffic_light_map_based_detector/src/node.cpp @@ -158,7 +158,7 @@ MapBasedDetector::MapBasedDetector(const rclcpp::NodeOptions & node_options) } // subscribers - map_sub_ = create_subscription( + map_sub_ = create_subscription( "~/input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&MapBasedDetector::mapCallback, this, _1)); camera_info_sub_ = create_subscription( @@ -380,7 +380,7 @@ bool MapBasedDetector::getTrafficLightRoi( } void MapBasedDetector::mapCallback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_msg) { lanelet_map_ptr_ = std::make_shared(); diff --git a/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp b/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp index 390b0f590b637..3ae2424fd7ff4 100644 --- a/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp +++ b/perception/traffic_light_multi_camera_fusion/include/traffic_light_multi_camera_fusion/node.hpp @@ -17,7 +17,7 @@ #include -#include +#include #include #include #include @@ -83,7 +83,7 @@ class MultiCameraFusion : public rclcpp::Node const CamInfoType::ConstSharedPtr cam_info_msg, const RoiArrayType::ConstSharedPtr roi_msg, const SignalArrayType::ConstSharedPtr signal_msg); - void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg); + void mapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_msg); void multiCameraFusion(std::map & fused_record_map); @@ -105,7 +105,7 @@ class MultiCameraFusion : public rclcpp::Node std::vector>> cam_info_subs_; std::vector> exact_sync_subs_; std::vector> approximate_sync_subs_; - rclcpp::Subscription::SharedPtr map_sub_; + rclcpp::Subscription::SharedPtr map_sub_; rclcpp::Publisher::SharedPtr signal_pub_; /* diff --git a/perception/traffic_light_multi_camera_fusion/package.xml b/perception/traffic_light_multi_camera_fusion/package.xml index b08ccfe668085..36dce830a2595 100644 --- a/perception/traffic_light_multi_camera_fusion/package.xml +++ b/perception/traffic_light_multi_camera_fusion/package.xml @@ -12,7 +12,7 @@ autoware_cmake - autoware_auto_mapping_msgs + autoware_map_msgs autoware_perception_msgs lanelet2_extension rclcpp diff --git a/perception/traffic_light_multi_camera_fusion/src/node.cpp b/perception/traffic_light_multi_camera_fusion/src/node.cpp index 1582040648624..16c96dd5bba30 100644 --- a/perception/traffic_light_multi_camera_fusion/src/node.cpp +++ b/perception/traffic_light_multi_camera_fusion/src/node.cpp @@ -176,7 +176,7 @@ MultiCameraFusion::MultiCameraFusion(const rclcpp::NodeOptions & node_options) } } - map_sub_ = create_subscription( + map_sub_ = create_subscription( "~/input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&MultiCameraFusion::mapCallback, this, _1)); signal_pub_ = create_publisher("~/output/traffic_signals", rclcpp::QoS{1}); @@ -205,7 +205,7 @@ void MultiCameraFusion::trafficSignalRoiCallback( } void MultiCameraFusion::mapCallback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_msg) { lanelet::LaneletMapPtr lanelet_map_ptr = std::make_shared(); diff --git a/perception/traffic_light_occlusion_predictor/README.md b/perception/traffic_light_occlusion_predictor/README.md index 312f9abccc464..45c84295bf1de 100644 --- a/perception/traffic_light_occlusion_predictor/README.md +++ b/perception/traffic_light_occlusion_predictor/README.md @@ -14,7 +14,7 @@ If no point cloud is received or all point clouds have very large stamp differen | Name | Type | Description | | -------------------- | --------------------------------------------------- | ------------------------ | -| `~input/vector_map` | autoware_auto_mapping_msgs::HADMapBin | vector map | +| `~input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | | `~/input/rois` | autoware_auto_perception_msgs::TrafficLightRoiArray | traffic light detections | | `~input/camera_info` | sensor_msgs::CameraInfo | target camera parameter | | `~/input/cloud` | sensor_msgs::PointCloud2 | LiDAR point cloud | diff --git a/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp index 71930c65f88c9..589926790fad7 100644 --- a/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp +++ b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp @@ -20,7 +20,7 @@ #include #include -#include +#include #include #include #include @@ -62,7 +62,7 @@ class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node * * @param input_msg */ - void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg); + void mapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_msg); /** * @brief subscribers * @@ -73,7 +73,7 @@ class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node const sensor_msgs::msg::CameraInfo::ConstSharedPtr in_cam_info_msg, const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg); - rclcpp::Subscription::SharedPtr map_sub_; + rclcpp::Subscription::SharedPtr map_sub_; /** * @brief publishers * diff --git a/perception/traffic_light_occlusion_predictor/package.xml b/perception/traffic_light_occlusion_predictor/package.xml index 49a67d68057d9..bc816cacbce13 100644 --- a/perception/traffic_light_occlusion_predictor/package.xml +++ b/perception/traffic_light_occlusion_predictor/package.xml @@ -13,7 +13,7 @@ autoware_cmake autoware_auto_geometry - autoware_auto_mapping_msgs + autoware_map_msgs geometry_msgs image_geometry lanelet2_extension diff --git a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp index c460f6a623bc4..fa8c3702d8f7a 100644 --- a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp +++ b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp @@ -50,7 +50,7 @@ TrafficLightOcclusionPredictorNodelet::TrafficLightOcclusionPredictorNodelet( using std::placeholders::_4; // subscribers - map_sub_ = create_subscription( + map_sub_ = create_subscription( "~/input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&TrafficLightOcclusionPredictorNodelet::mapCallback, this, _1)); @@ -81,7 +81,7 @@ TrafficLightOcclusionPredictorNodelet::TrafficLightOcclusionPredictorNodelet( } void TrafficLightOcclusionPredictorNodelet::mapCallback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_msg) { traffic_light_position_map_.clear(); auto lanelet_map_ptr = std::make_shared(); diff --git a/perception/traffic_light_visualization/README.md b/perception/traffic_light_visualization/README.md index 5d99d6614a1ae..3f40b3649f9a4 100644 --- a/perception/traffic_light_visualization/README.md +++ b/perception/traffic_light_visualization/README.md @@ -20,7 +20,7 @@ The `traffic_light_visualization` is a package that includes two visualizing nod | Name | Type | Description | | -------------------- | ------------------------------------------------ | ------------------------ | | `~/input/tl_state` | `tier4_perception_msgs::msg::TrafficSignalArray` | status of traffic lights | -| `~/input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | +| `~/input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map | #### Output diff --git a/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp b/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp index 3f83cf6e926ad..96e06ee44d301 100644 --- a/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp +++ b/perception/traffic_light_visualization/include/traffic_light_map_visualizer/node.hpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include #include @@ -36,13 +36,12 @@ class TrafficLightMapVisualizerNode : public rclcpp::Node void trafficSignalsCallback( const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr input_traffic_signals_msg); - void binMapCallback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_map_msg); + void binMapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_map_msg); private: rclcpp::Publisher::SharedPtr light_marker_pub_; rclcpp::Subscription::SharedPtr tl_state_sub_; - rclcpp::Subscription::SharedPtr vector_map_sub_; + rclcpp::Subscription::SharedPtr vector_map_sub_; std::vector aw_tl_reg_elems_; }; diff --git a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp index 53e06e47a1873..86f6758e895c6 100644 --- a/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp +++ b/perception/traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp @@ -115,7 +115,7 @@ TrafficLightMapVisualizerNode::TrafficLightMapVisualizerNode( tl_state_sub_ = create_subscription( "~/input/tl_state", 1, std::bind(&TrafficLightMapVisualizerNode::trafficSignalsCallback, this, _1)); - vector_map_sub_ = create_subscription( + vector_map_sub_ = create_subscription( "~/input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&TrafficLightMapVisualizerNode::binMapCallback, this, _1)); } @@ -197,7 +197,7 @@ void TrafficLightMapVisualizerNode::trafficSignalsCallback( } void TrafficLightMapVisualizerNode::binMapCallback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_map_msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_map_msg) { lanelet::LaneletMapPtr viz_lanelet_map(new lanelet::LaneletMap); diff --git a/planning/behavior_path_planner/README.md b/planning/behavior_path_planner/README.md index 0c0c7c806c119..cb781bebf90c9 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -93,8 +93,8 @@ The current behavior tree structure is shown below. Each modules (LaneChange, Av | Name | Type | Description | | :----------------------------- | :----------------------------------------------------- | :------------------------------------------------------------------------------------ | -| ~/input/route | `autoware_auto_mapping_msgs::msg::LaneletRoute` | current route from start to goal. | -| ~/input/vector_map | `autoware_auto_mapping_msgs::msg::HADMapBin` | map information. | +| ~/input/route | `autoware_planning_msgs::msg::LaneletRoute` | current route from start to goal. | +| ~/input/vector_map | `autoware_map_msgs::msg::LaneletMapBin` | map information. | | ~/input/objects | `autoware_auto_perception_msgs::msg::PredictedObjects` | dynamic objects from perception module. | | ~/input/occupancy_grid_map/map | `nav_msgs::msg::OccupancyGrid` | occupancy grid map from perception module. This is used for only Goal Planner module. | | ~/input/kinematic_state | `nav_msgs::msg::Odometry` | for ego velocity. | diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 1a9b23be00a3f..665f05318b6de 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -23,12 +23,12 @@ #include "tier4_planning_msgs/msg/detail/lane_change_debug_msg_array__struct.hpp" #include -#include #include #include #include #include #include +#include #include #include #include @@ -51,13 +51,13 @@ namespace behavior_path_planner { using autoware_adapi_v1_msgs::msg::OperationModeState; -using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_perception_msgs::msg::PredictedObject; using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathWithLaneId; using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; using autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand; +using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::PoseWithUuidStamped; @@ -87,7 +87,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node private: rclcpp::Subscription::SharedPtr route_subscriber_; - rclcpp::Subscription::SharedPtr vector_map_subscriber_; + rclcpp::Subscription::SharedPtr vector_map_subscriber_; rclcpp::Subscription::SharedPtr velocity_subscriber_; rclcpp::Subscription::SharedPtr acceleration_subscriber_; rclcpp::Subscription::SharedPtr scenario_subscriber_; @@ -116,7 +116,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node std::unique_ptr steering_factor_interface_ptr_; Scenario::SharedPtr current_scenario_{nullptr}; - HADMapBin::ConstSharedPtr map_ptr_{nullptr}; + LaneletMapBin::ConstSharedPtr map_ptr_{nullptr}; LaneletRoute::ConstSharedPtr route_ptr_{nullptr}; bool has_received_map_{false}; bool has_received_route_{false}; @@ -139,7 +139,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node void onOccupancyGrid(const OccupancyGrid::ConstSharedPtr msg); void onCostMap(const OccupancyGrid::ConstSharedPtr msg); void onTrafficSignals(const TrafficSignalArray::ConstSharedPtr msg); - void onMap(const HADMapBin::ConstSharedPtr map_msg); + void onMap(const LaneletMapBin::ConstSharedPtr map_msg); void onRoute(const LaneletRoute::ConstSharedPtr route_msg); void onOperationMode(const OperationModeState::ConstSharedPtr msg); void onLateralOffset(const LateralOffset::ConstSharedPtr msg); diff --git a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp index 99cd5cac2b9d9..a86301b65e739 100644 --- a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp @@ -176,7 +176,7 @@ TEST(DrivableAreaExpansionProjection, expand_drivable_area) { drivable_area_expansion::DrivableAreaExpansionParameters params; drivable_area_expansion::PredictedObjects dynamic_objects; - autoware_auto_mapping_msgs::msg::HADMapBin map; + autoware_map_msgs::msg::LaneletMapBin map; lanelet::LaneletMapPtr empty_lanelet_map_ptr = std::make_shared(); lanelet::utils::conversion::toBinMsg(empty_lanelet_map_ptr, &map); route_handler::RouteHandler route_handler(map); diff --git a/planning/behavior_velocity_planner/README.md b/planning/behavior_velocity_planner/README.md index 519e68764b450..cad47c16c1452 100644 --- a/planning/behavior_velocity_planner/README.md +++ b/planning/behavior_velocity_planner/README.md @@ -32,7 +32,7 @@ So for example, in order to stop at a stop line with the vehicles' front on the | Name | Type | Description | | ----------------------------------------- | ---------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------- | | `~input/path_with_lane_id` | autoware_auto_planning_msgs::msg::PathWithLaneId | path with lane_id | -| `~input/vector_map` | autoware_auto_mapping_msgs::msg::HADMapBin | vector map | +| `~input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | | `~input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle velocity | | `~input/dynamic_objects` | autoware_auto_perception_msgs::msg::PredictedObjects | dynamic objects | | `~input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud | diff --git a/planning/behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/package.xml index 1357b555f0ba4..62cd85b4f469e 100644 --- a/planning/behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/package.xml @@ -34,9 +34,9 @@ rosidl_default_generators - autoware_auto_mapping_msgs autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_map_msgs behavior_velocity_planner_common diagnostic_msgs eigen diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index ec28656d8f866..ad740da68e93a 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -99,7 +99,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio sub_acceleration_ = this->create_subscription( "~/input/accel", 1, std::bind(&BehaviorVelocityPlannerNode::onAcceleration, this, _1), createSubscriptionOptions(this)); - sub_lanelet_map_ = this->create_subscription( + sub_lanelet_map_ = this->create_subscription( "~/input/vector_map", rclcpp::QoS(10).transient_local(), std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1), createSubscriptionOptions(this)); @@ -307,7 +307,7 @@ void BehaviorVelocityPlannerNode::onParam() } void BehaviorVelocityPlannerNode::onLaneletMap( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg) { std::lock_guard lock(mutex_); diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp index ded1d08700a1d..7599ff84561d1 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/src/node.hpp @@ -23,10 +23,10 @@ #include #include -#include #include #include #include +#include #include #include #include @@ -45,7 +45,7 @@ namespace behavior_velocity_planner { -using autoware_auto_mapping_msgs::msg::HADMapBin; +using autoware_map_msgs::msg::LaneletMapBin; using behavior_velocity_planner::srv::LoadPlugin; using behavior_velocity_planner::srv::UnloadPlugin; using tier4_planning_msgs::msg::VelocityLimit; @@ -68,7 +68,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_no_ground_pointcloud_; rclcpp::Subscription::SharedPtr sub_vehicle_odometry_; rclcpp::Subscription::SharedPtr sub_acceleration_; - rclcpp::Subscription::SharedPtr sub_lanelet_map_; + rclcpp::Subscription::SharedPtr sub_lanelet_map_; rclcpp::Subscription::SharedPtr sub_traffic_signals_; rclcpp::Subscription::SharedPtr @@ -83,7 +83,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node void onNoGroundPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); void onAcceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg); - void onLaneletMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg); + void onLaneletMap(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg); void onTrafficSignals( const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg); void onVirtualTrafficLightStates( @@ -107,7 +107,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node PlannerData planner_data_; BehaviorVelocityPlannerManager planner_manager_; bool is_driving_forward_{true}; - HADMapBin::ConstSharedPtr map_ptr_{nullptr}; + LaneletMapBin::ConstSharedPtr map_ptr_{nullptr}; bool has_received_map_; rclcpp::Service::SharedPtr srv_load_plugin_; diff --git a/planning/behavior_velocity_planner/src/planner_manager.hpp b/planning/behavior_velocity_planner/src/planner_manager.hpp index 7485e5faba8bf..c75807ab926bb 100644 --- a/planning/behavior_velocity_planner/src/planner_manager.hpp +++ b/planning/behavior_velocity_planner/src/planner_manager.hpp @@ -20,10 +20,10 @@ #include #include -#include #include #include #include +#include #include #include diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp index 620fc61ec5360..23f3b32060aa2 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/planner_data.hpp @@ -21,8 +21,8 @@ #include #include -#include #include +#include #include #include #include diff --git a/planning/behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner_common/package.xml index aedbab65068fb..7062eafbe4dc9 100644 --- a/planning/behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner_common/package.xml @@ -18,9 +18,9 @@ eigen3_cmake_module autoware_adapi_v1_msgs - autoware_auto_mapping_msgs autoware_auto_planning_msgs autoware_auto_tf2 + autoware_map_msgs autoware_perception_msgs diagnostic_msgs eigen diff --git a/planning/costmap_generator/README.md b/planning/costmap_generator/README.md index a38a1a4d7ff9b..f8a1b4933d9bd 100644 --- a/planning/costmap_generator/README.md +++ b/planning/costmap_generator/README.md @@ -10,7 +10,7 @@ This node reads `PointCloud` and/or `DynamicObjectArray` and creates an `Occupan | ------------------------- | ----------------------------------------------- | ---------------------------------------------------------------------------- | | `~input/objects` | autoware_auto_perception_msgs::PredictedObjects | predicted objects, for obstacles areas | | `~input/points_no_ground` | sensor_msgs::PointCloud2 | ground-removed points, for obstacle areas which can't be detected as objects | -| `~input/vector_map` | autoware_auto_mapping_msgs::HADMapBin | vector map, for drivable areas | +| `~input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map, for drivable areas | | `~input/scenario` | tier4_planning_msgs::Scenario | scenarios to be activated, for node activation | ### Output topics diff --git a/planning/costmap_generator/include/costmap_generator/costmap_generator.hpp b/planning/costmap_generator/include/costmap_generator/costmap_generator.hpp index 87fded0c01891..e46500259dc93 100644 --- a/planning/costmap_generator/include/costmap_generator/costmap_generator.hpp +++ b/planning/costmap_generator/include/costmap_generator/costmap_generator.hpp @@ -53,8 +53,8 @@ #include #include -#include #include +#include #include #include @@ -116,7 +116,7 @@ class CostmapGenerator : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_points_; rclcpp::Subscription::SharedPtr sub_objects_; - rclcpp::Subscription::SharedPtr sub_lanelet_bin_map_; + rclcpp::Subscription::SharedPtr sub_lanelet_bin_map_; rclcpp::Subscription::SharedPtr sub_scenario_; rclcpp::TimerBase::SharedPtr timer_; @@ -143,7 +143,7 @@ class CostmapGenerator : public rclcpp::Node void initLaneletMap(); /// \brief callback for loading lanelet2 map - void onLaneletMapBin(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg); + void onLaneletMapBin(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg); /// \brief callback for DynamicObjectArray /// \param[in] in_objects input DynamicObjectArray usually from prediction or perception diff --git a/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp b/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp index afe345490201b..a82d8000ad077 100644 --- a/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp +++ b/planning/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp @@ -201,7 +201,7 @@ CostmapGenerator::CostmapGenerator(const rclcpp::NodeOptions & node_options) sub_points_ = this->create_subscription( "~/input/points_no_ground", rclcpp::SensorDataQoS(), std::bind(&CostmapGenerator::onPoints, this, _1)); - sub_lanelet_bin_map_ = this->create_subscription( + sub_lanelet_bin_map_ = this->create_subscription( "~/input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&CostmapGenerator::onLaneletMapBin, this, _1)); sub_scenario_ = this->create_subscription( @@ -263,7 +263,7 @@ void CostmapGenerator::loadParkingAreasFromLaneletMap( } void CostmapGenerator::onLaneletMapBin( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg) { lanelet_map_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_); diff --git a/planning/costmap_generator/package.xml b/planning/costmap_generator/package.xml index ae124a1774881..0015787e25d62 100644 --- a/planning/costmap_generator/package.xml +++ b/planning/costmap_generator/package.xml @@ -15,8 +15,8 @@ ament_cmake_auto autoware_cmake - autoware_auto_mapping_msgs autoware_auto_perception_msgs + autoware_map_msgs grid_map_ros lanelet2_extension libpcl-all-dev diff --git a/planning/mission_planner/README.md b/planning/mission_planner/README.md index 3b649168884e6..f3eff68b08b5c 100644 --- a/planning/mission_planner/README.md +++ b/planning/mission_planner/README.md @@ -40,10 +40,10 @@ In current Autoware.universe, only Lanelet2 map format is supported. ### Subscriptions -| Name | Type | Description | -| --------------------- | ------------------------------------ | ---------------------- | -| `input/vector_map` | autoware_auto_mapping_msgs/HADMapBin | vector map of Lanelet2 | -| `input/modified_goal` | geometry_msgs/PoseWithUuidStamped | modified goal pose | +| Name | Type | Description | +| --------------------- | ----------------------------------- | ---------------------- | +| `input/vector_map` | autoware_map_msgs/msg/LaneletMapBin | vector map of Lanelet2 | +| `input/modified_goal` | geometry_msgs/PoseWithUuidStamped | modified goal pose | ### Publications @@ -59,7 +59,7 @@ In current Autoware.universe, only Lanelet2 map format is supported. ![route_sections](./media/route_sections.svg) Route section, whose type is `autoware_planning_msgs/LaneletSegment`, is a "slice" of a road that bundles lane changeable lanes. -Note that the most atomic unit of route is `autoware_auto_mapping_msgs/LaneletPrimitive`, which has the unique id of a lane in a vector map and its type. +Note that the most atomic unit of route is `autoware_planning_msgs/LaneletPrimitive`, which has the unique id of a lane in a vector map and its type. Therefore, route message does not contain geometric information about the lane since we did not want to have planning module’s message to have dependency on map data structure. The ROS message of route section contains following three elements for each route section. diff --git a/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp b/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp index 96de30ddab592..80e197e2a8ef9 100644 --- a/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp +++ b/planning/mission_planner/include/mission_planner/mission_planner_plugin.hpp @@ -17,7 +17,7 @@ #include -#include +#include #include #include #include @@ -32,12 +32,12 @@ class PlannerPlugin public: using RoutePoints = std::vector; using LaneletRoute = autoware_planning_msgs::msg::LaneletRoute; - using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; using MarkerArray = visualization_msgs::msg::MarkerArray; virtual ~PlannerPlugin() = default; virtual void initialize(rclcpp::Node * node) = 0; - virtual void initialize(rclcpp::Node * node, const HADMapBin::ConstSharedPtr msg) = 0; + virtual void initialize(rclcpp::Node * node, const LaneletMapBin::ConstSharedPtr msg) = 0; virtual bool ready() const = 0; virtual LaneletRoute plan(const RoutePoints & points) = 0; virtual MarkerArray visualize(const LaneletRoute & route) const = 0; diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 673519b6f7a0e..649d1a00e54e5 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -159,12 +159,12 @@ void DefaultPlanner::initialize_common(rclcpp::Node * node) void DefaultPlanner::initialize(rclcpp::Node * node) { initialize_common(node); - map_subscriber_ = node_->create_subscription( + map_subscriber_ = node_->create_subscription( "input/vector_map", rclcpp::QoS{10}.transient_local(), std::bind(&DefaultPlanner::map_callback, this, std::placeholders::_1)); } -void DefaultPlanner::initialize(rclcpp::Node * node, const HADMapBin::ConstSharedPtr msg) +void DefaultPlanner::initialize(rclcpp::Node * node, const LaneletMapBin::ConstSharedPtr msg) { initialize_common(node); map_callback(msg); @@ -175,7 +175,7 @@ bool DefaultPlanner::ready() const return is_graph_ready_; } -void DefaultPlanner::map_callback(const HADMapBin::ConstSharedPtr msg) +void DefaultPlanner::map_callback(const LaneletMapBin::ConstSharedPtr msg) { route_handler_.setMap(*msg); lanelet_map_ptr_ = std::make_shared(); diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index 251d0db533182..e875c64c30c54 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -20,7 +20,7 @@ #include #include -#include +#include #include #include @@ -45,7 +45,7 @@ class DefaultPlanner : public mission_planner::PlannerPlugin { public: void initialize(rclcpp::Node * node) override; - void initialize(rclcpp::Node * node, const HADMapBin::ConstSharedPtr msg) override; + void initialize(rclcpp::Node * node, const LaneletMapBin::ConstSharedPtr msg) override; bool ready() const override; LaneletRoute plan(const RoutePoints & points) override; MarkerArray visualize(const LaneletRoute & route) const override; @@ -66,11 +66,11 @@ class DefaultPlanner : public mission_planner::PlannerPlugin DefaultPlannerParameters param_; rclcpp::Node * node_; - rclcpp::Subscription::SharedPtr map_subscriber_; + rclcpp::Subscription::SharedPtr map_subscriber_; rclcpp::Publisher::SharedPtr pub_goal_footprint_marker_; void initialize_common(rclcpp::Node * node); - void map_callback(const HADMapBin::ConstSharedPtr msg); + void map_callback(const LaneletMapBin::ConstSharedPtr msg); bool check_goal_footprint( const lanelet::ConstLanelet & current_lanelet, const lanelet::ConstLanelet & combined_prev_lanelet, diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 513a5b4c25a2e..c2e099a7f4d48 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -21,7 +21,7 @@ #include #include -#include +#include #include #include @@ -100,7 +100,7 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) std::bind(&MissionPlanner::on_reroute_availability, this, std::placeholders::_1)); const auto durable_qos = rclcpp::QoS(1).transient_local(); - sub_vector_map_ = create_subscription( + sub_vector_map_ = create_subscription( "input/vector_map", durable_qos, std::bind(&MissionPlanner::on_map, this, std::placeholders::_1)); sub_modified_goal_ = create_subscription( @@ -169,7 +169,7 @@ void MissionPlanner::on_reroute_availability(const RerouteAvailability::ConstSha reroute_availability_ = msg; } -void MissionPlanner::on_map(const HADMapBin::ConstSharedPtr msg) +void MissionPlanner::on_map(const LaneletMapBin::ConstSharedPtr msg) { map_ptr_ = msg; } diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index ea44d2643e186..6a10718695f4e 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -45,7 +45,7 @@ using PoseStamped = geometry_msgs::msg::PoseStamped; using PoseWithUuidStamped = autoware_planning_msgs::msg::PoseWithUuidStamped; using LaneletRoute = autoware_planning_msgs::msg::LaneletRoute; using LaneletPrimitive = autoware_planning_msgs::msg::LaneletPrimitive; -using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; +using LaneletMapBin = autoware_map_msgs::msg::LaneletMapBin; using MarkerArray = visualization_msgs::msg::MarkerArray; using ClearRoute = planning_interface::ClearRoute; using SetRoutePoints = planning_interface::SetRoutePoints; @@ -74,15 +74,15 @@ class MissionPlanner : public rclcpp::Node PoseStamped transform_pose(const PoseStamped & input); rclcpp::Subscription::SharedPtr sub_odometry_; - rclcpp::Subscription::SharedPtr sub_vector_map_; + rclcpp::Subscription::SharedPtr sub_vector_map_; rclcpp::Subscription::SharedPtr sub_reroute_availability_; rclcpp::Subscription::SharedPtr sub_modified_goal_; Odometry::ConstSharedPtr odometry_; - HADMapBin::ConstSharedPtr map_ptr_; + LaneletMapBin::ConstSharedPtr map_ptr_; RerouteAvailability::ConstSharedPtr reroute_availability_; void on_odometry(const Odometry::ConstSharedPtr msg); - void on_map(const HADMapBin::ConstSharedPtr msg); + void on_map(const LaneletMapBin::ConstSharedPtr msg); void on_reroute_availability(const RerouteAvailability::ConstSharedPtr msg); void on_modified_goal(const PoseWithUuidStamped::ConstSharedPtr msg); diff --git a/planning/obstacle_stop_planner/README.md b/planning/obstacle_stop_planner/README.md index ef5b0facd236e..99e4217d0c9ff 100644 --- a/planning/obstacle_stop_planner/README.md +++ b/planning/obstacle_stop_planner/README.md @@ -17,7 +17,7 @@ | --------------------------- | ----------------------------------------------- | ------------------- | | `~/input/pointcloud` | sensor_msgs::PointCloud2 | obstacle pointcloud | | `~/input/trajectory` | autoware_auto_planning_msgs::Trajectory | trajectory | -| `~/input/vector_map` | autoware_auto_mapping_msgs::HADMapBin | vector map | +| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | | `~/input/odometry` | nav_msgs::Odometry | vehicle velocity | | `~/input/dynamic_objects` | autoware_auto_perception_msgs::PredictedObjects | dynamic objects | | `~/input/expand_stop_range` | tier4_planning_msgs::msg::ExpandStopRange | expand stop range | diff --git a/planning/obstacle_velocity_limiter/README.md b/planning/obstacle_velocity_limiter/README.md index 36aa35bb31156..16b1cb60b853f 100644 --- a/planning/obstacle_velocity_limiter/README.md +++ b/planning/obstacle_velocity_limiter/README.md @@ -153,7 +153,7 @@ For example a value of `1` means all trajectory points will be evaluated while a | `~/input/obstacle_pointcloud` | `sensor_msgs/PointCloud2` | Pointcloud containing only obstacle points | | `~/input/dynamic_obstacles` | `autoware_auto_perception_msgs/PredictedObjects` | Dynamic objects | | `~/input/odometry` | `nav_msgs/Odometry` | Odometry used to retrieve the current ego velocity | -| `~/input/map` | `autoware_auto_mapping_msgs/HADMapBin` | Vector map used to retrieve static obstacles | +| `~/input/map` | `autoware_map_msgs/LaneletMapBin` | Vector map used to retrieve static obstacles | ### Outputs diff --git a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp index cbdd390183d61..7dcb86f463dd6 100644 --- a/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp +++ b/planning/obstacle_velocity_limiter/include/obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp @@ -24,9 +24,9 @@ #include #include -#include #include #include +#include #include #include #include @@ -68,7 +68,7 @@ class ObstacleVelocityLimiterNode : public rclcpp::Node sub_pointcloud_; //!< @brief subscriber for obstacle pointcloud rclcpp::Subscription::SharedPtr sub_odom_; //!< @brief subscriber for the current velocity - rclcpp::Subscription::SharedPtr map_sub_; + rclcpp::Subscription::SharedPtr map_sub_; // cached inputs PredictedObjects::ConstSharedPtr dynamic_obstacles_ptr_; diff --git a/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp b/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp index 086d76e9ef0fe..dedc4d9e3ee1f 100644 --- a/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp +++ b/planning/obstacle_velocity_limiter/src/obstacle_velocity_limiter_node.cpp @@ -57,9 +57,9 @@ ObstacleVelocityLimiterNode::ObstacleVelocityLimiterNode(const rclcpp::NodeOptio sub_odom_ = create_subscription( "~/input/odometry", rclcpp::QoS{1}, [this](const nav_msgs::msg::Odometry::ConstSharedPtr msg) { current_odometry_ptr_ = msg; }); - map_sub_ = create_subscription( + map_sub_ = create_subscription( "~/input/map", rclcpp::QoS{1}.transient_local(), - [this](const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg) { + [this](const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg) { lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr_); static_map_obstacles_ = extractStaticObstacles(*lanelet_map_ptr_, obstacle_params_.static_map_tags); diff --git a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp index c5a30be126661..9acd3d47335d1 100644 --- a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp +++ b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp @@ -36,12 +36,12 @@ #include #include -#include #include #include #include #include #include +#include #include #include #include @@ -75,11 +75,11 @@ namespace planning_test_utils { using autoware_adapi_v1_msgs::msg::OperationModeState; -using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathWithLaneId; using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::TrafficSignalArray; using autoware_planning_msgs::msg::LaneletRoute; using geometry_msgs::msg::AccelWithCovarianceStamped; @@ -193,7 +193,7 @@ class PlanningInterfaceTestManager rclcpp::Publisher::SharedPtr expand_stop_range_pub_; rclcpp::Publisher::SharedPtr occupancy_grid_pub_; rclcpp::Publisher::SharedPtr cost_map_pub_; - rclcpp::Publisher::SharedPtr map_pub_; + rclcpp::Publisher::SharedPtr map_pub_; rclcpp::Publisher::SharedPtr scenario_pub_; rclcpp::Publisher::SharedPtr parking_scenario_pub_; rclcpp::Publisher::SharedPtr lane_driving_scenario_pub_; diff --git a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp index 211f2179638a6..be64e0527d943 100644 --- a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp +++ b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp @@ -26,10 +26,10 @@ #include #include -#include #include #include #include +#include #include #include #include @@ -57,11 +57,11 @@ namespace test_utils { -using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using autoware_auto_planning_msgs::msg::PathWithLaneId; using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_map_msgs::msg::LaneletMapBin; using autoware_planning_msgs::msg::LaneletPrimitive; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::LaneletSegment; @@ -148,18 +148,18 @@ lanelet::LaneletMapPtr loadMap(const std::string & lanelet2_filename) return nullptr; } -HADMapBin convertToMapBinMsg( +LaneletMapBin convertToMapBinMsg( const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now) { std::string format_version{}, map_version{}; lanelet::io_handlers::AutowareOsmParser::parseVersions( lanelet2_filename, &format_version, &map_version); - HADMapBin map_bin_msg; + LaneletMapBin map_bin_msg; map_bin_msg.header.stamp = now; map_bin_msg.header.frame_id = "map"; - map_bin_msg.format_version = format_version; - map_bin_msg.map_version = map_version; + map_bin_msg.version_map_format = format_version; + map_bin_msg.version_map = map_version; lanelet::utils::conversion::toBinMsg(map, &map_bin_msg); return map_bin_msg; @@ -194,7 +194,7 @@ OccupancyGrid makeCostMapMsg(size_t width = 150, size_t height = 150, double res return costmap_msg; } -HADMapBin makeMapBinMsg() +LaneletMapBin makeMapBinMsg() { const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); @@ -203,7 +203,7 @@ HADMapBin makeMapBinMsg() // load map from file const auto map = loadMap(lanelet2_path); if (!map) { - return autoware_auto_mapping_msgs::msg::HADMapBin_>{}; + return autoware_map_msgs::msg::LaneletMapBin_>{}; } // overwrite centerline @@ -404,7 +404,7 @@ void createPublisherWithQoS( custom_qos_profile.reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE); custom_qos_profile.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); publisher = rclcpp::create_publisher(test_node, topic_name, custom_qos_profile); - } else if constexpr (std::is_same_v) { + } else if constexpr (std::is_same_v) { rclcpp::QoS qos(rclcpp::KeepLast(1)); qos.reliable(); qos.transient_local(); diff --git a/planning/planning_test_utils/package.xml b/planning/planning_test_utils/package.xml index 23bfb2f44cb96..99a682a37059b 100644 --- a/planning/planning_test_utils/package.xml +++ b/planning/planning_test_utils/package.xml @@ -14,9 +14,9 @@ autoware_cmake autoware_auto_control_msgs - autoware_auto_mapping_msgs autoware_auto_planning_msgs autoware_auto_vehicle_msgs + autoware_map_msgs autoware_perception_msgs autoware_planning_msgs component_interface_specs diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index b12ca7f648a7d..d018af6dcbab0 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -17,8 +17,8 @@ #include -#include #include +#include #include #include #include @@ -35,8 +35,8 @@ namespace route_handler { -using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_planning_msgs::msg::PathWithLaneId; +using autoware_map_msgs::msg::LaneletMapBin; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::LaneletSegment; using geometry_msgs::msg::Pose; @@ -53,10 +53,10 @@ class RouteHandler { public: RouteHandler() = default; - explicit RouteHandler(const HADMapBin & map_msg); + explicit RouteHandler(const LaneletMapBin & map_msg); // non-const methods - void setMap(const HADMapBin & map_msg); + void setMap(const LaneletMapBin & map_msg); void setRoute(const LaneletRoute & route_msg); void setRouteLanelets(const lanelet::ConstLanelets & path_lanelets); void clearRoute(); diff --git a/planning/route_handler/package.xml b/planning/route_handler/package.xml index 60adfb1531104..ac29a3db18d5d 100644 --- a/planning/route_handler/package.xml +++ b/planning/route_handler/package.xml @@ -19,8 +19,8 @@ ament_lint_auto autoware_lint_common - autoware_auto_mapping_msgs autoware_auto_planning_msgs + autoware_map_msgs autoware_planning_msgs geometry_msgs lanelet2_extension diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index d74a8712a6e3f..0c5a135b0d1fb 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -132,13 +132,13 @@ std::string toString(const geometry_msgs::msg::Pose & pose) namespace route_handler { -RouteHandler::RouteHandler(const HADMapBin & map_msg) +RouteHandler::RouteHandler(const LaneletMapBin & map_msg) { setMap(map_msg); route_ptr_ = nullptr; } -void RouteHandler::setMap(const HADMapBin & map_msg) +void RouteHandler::setMap(const LaneletMapBin & map_msg) { lanelet_map_ptr_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg( diff --git a/planning/scenario_selector/README.md b/planning/scenario_selector/README.md index 3e02a3dbb84d9..530010fc1626d 100644 --- a/planning/scenario_selector/README.md +++ b/planning/scenario_selector/README.md @@ -10,7 +10,7 @@ | -------------------------------- | --------------------------------------- | ----------------------------------------------------- | | `~input/lane_driving/trajectory` | autoware_auto_planning_msgs::Trajectory | trajectory of LaneDriving scenario | | `~input/parking/trajectory` | autoware_auto_planning_msgs::Trajectory | trajectory of Parking scenario | -| `~input/lanelet_map` | autoware_auto_mapping_msgs::HADMapBin | | +| `~input/lanelet_map` | autoware_map_msgs::msg::LaneletMapBin | | | `~input/route` | autoware_planning_msgs::LaneletRoute | route and goal pose | | `~input/odometry` | nav_msgs::Odometry | for checking whether vehicle is stopped | | `is_parking_completed` | bool (implemented as rosparam) | whether all split trajectory of Parking are published | diff --git a/planning/scenario_selector/include/scenario_selector/scenario_selector_node.hpp b/planning/scenario_selector/include/scenario_selector/scenario_selector_node.hpp index 94969570d6b53..1bae0c469c948 100644 --- a/planning/scenario_selector/include/scenario_selector/scenario_selector_node.hpp +++ b/planning/scenario_selector/include/scenario_selector/scenario_selector_node.hpp @@ -17,8 +17,8 @@ #include -#include #include +#include #include #include #include @@ -47,7 +47,7 @@ class ScenarioSelectorNode : public rclcpp::Node public: explicit ScenarioSelectorNode(const rclcpp::NodeOptions & node_options); - void onMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg); + void onMap(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg); void onRoute(const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr msg); void onOdom(const nav_msgs::msg::Odometry::ConstSharedPtr msg); void onParkingState(const std_msgs::msg::Bool::ConstSharedPtr msg); @@ -67,7 +67,7 @@ class ScenarioSelectorNode : public rclcpp::Node private: rclcpp::TimerBase::SharedPtr timer_; - rclcpp::Subscription::SharedPtr sub_lanelet_map_; + rclcpp::Subscription::SharedPtr sub_lanelet_map_; rclcpp::Subscription::SharedPtr sub_route_; rclcpp::Subscription::SharedPtr sub_odom_; rclcpp::Subscription::SharedPtr diff --git a/planning/scenario_selector/package.xml b/planning/scenario_selector/package.xml index 53c29613a1de8..d7f1946cd9d37 100644 --- a/planning/scenario_selector/package.xml +++ b/planning/scenario_selector/package.xml @@ -16,8 +16,8 @@ ament_cmake_auto autoware_cmake - autoware_auto_mapping_msgs autoware_auto_planning_msgs + autoware_map_msgs lanelet2_extension nav_msgs planning_test_utils diff --git a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp index 1d5c7b44dcc45..ca9edcf2c9bb2 100644 --- a/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp +++ b/planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp @@ -185,8 +185,7 @@ void ScenarioSelectorNode::updateCurrentScenario() } } -void ScenarioSelectorNode::onMap( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg) +void ScenarioSelectorNode::onMap(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg) { lanelet_map_ptr_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg( @@ -348,7 +347,7 @@ ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_opti "input/parking/trajectory", rclcpp::QoS{1}, std::bind(&ScenarioSelectorNode::onParkingTrajectory, this, std::placeholders::_1)); - sub_lanelet_map_ = this->create_subscription( + sub_lanelet_map_ = this->create_subscription( "input/lanelet_map", rclcpp::QoS{1}.transient_local(), std::bind(&ScenarioSelectorNode::onMap, this, std::placeholders::_1)); sub_route_ = this->create_subscription( diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp index 1a700d36deaaf..2d7b7314e5e32 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp @@ -17,24 +17,24 @@ #include "route_handler/route_handler.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" -#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" #include "autoware_auto_perception_msgs/msg/predicted_objects.hpp" #include "autoware_auto_planning_msgs/msg/path.hpp" #include "autoware_auto_planning_msgs/msg/path_point.hpp" #include "autoware_auto_planning_msgs/msg/trajectory.hpp" #include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" +#include "autoware_map_msgs/msg/lanelet_map_bin.hpp" #include "autoware_planning_msgs/msg/lanelet_route.hpp" #include "visualization_msgs/msg/marker_array.hpp" namespace static_centerline_optimizer { -using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathPoint; using autoware_auto_planning_msgs::msg::PathWithLaneId; using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using autoware_map_msgs::msg::LaneletMapBin; using autoware_planning_msgs::msg::LaneletRoute; using route_handler::RouteHandler; using tier4_autoware_utils::LinearRing2d; diff --git a/planning/static_centerline_optimizer/package.xml b/planning/static_centerline_optimizer/package.xml index 89976be5bdd47..4d2e5a77daaa3 100644 --- a/planning/static_centerline_optimizer/package.xml +++ b/planning/static_centerline_optimizer/package.xml @@ -15,9 +15,9 @@ rosidl_default_generators - autoware_auto_mapping_msgs autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_map_msgs behavior_path_planner geometry_msgs global_parameter_loader diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 4532eb66978cb..255e035be0c53 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -192,7 +192,8 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( : Node("static_centerline_optimizer", node_options) { // publishers - pub_map_bin_ = create_publisher("lanelet2_map_topic", create_transient_local_qos()); + pub_map_bin_ = + create_publisher("lanelet2_map_topic", create_transient_local_qos()); pub_raw_path_with_lane_id_ = create_publisher("input_centerline", create_transient_local_qos()); pub_raw_path_ = create_publisher("debug/raw_centerline", create_transient_local_qos()); @@ -247,7 +248,7 @@ void StaticCenterlineOptimizerNode::run() void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_file_path) { // load map by the map_loader package - map_bin_ptr_ = [&]() -> HADMapBin::ConstSharedPtr { + map_bin_ptr_ = [&]() -> LaneletMapBin::ConstSharedPtr { // load map lanelet::LaneletMapPtr map_ptr; tier4_map_msgs::msg::MapProjectorInfo map_projector_info; @@ -261,7 +262,7 @@ void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_ const auto map_bin_msg = Lanelet2MapLoaderNode::create_map_bin_msg(map_ptr, lanelet2_input_file_path, now()); - return std::make_shared(map_bin_msg); + return std::make_shared(map_bin_msg); }(); // check if map_bin_ptr_ is not null pointer diff --git a/sensing/pointcloud_preprocessor/docs/vector-map-filter.md b/sensing/pointcloud_preprocessor/docs/vector-map-filter.md index fedd3c081cdeb..c38a4c719fcf3 100644 --- a/sensing/pointcloud_preprocessor/docs/vector-map-filter.md +++ b/sensing/pointcloud_preprocessor/docs/vector-map-filter.md @@ -10,10 +10,10 @@ The `vector_map_filter` is a node that removes points on the outside of lane by ### Input -| Name | Type | Description | -| -------------------- | -------------------------------------------- | ---------------- | -| `~/input/points` | `sensor_msgs::msg::PointCloud2` | reference points | -| `~/input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map | +| Name | Type | Description | +| -------------------- | --------------------------------------- | ---------------- | +| `~/input/points` | `sensor_msgs::msg::PointCloud2` | reference points | +| `~/input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map | ### Output diff --git a/sensing/pointcloud_preprocessor/docs/vector-map-inside-area-filter.md b/sensing/pointcloud_preprocessor/docs/vector-map-inside-area-filter.md index 4bafac7872e78..bd2f7d98919d5 100644 --- a/sensing/pointcloud_preprocessor/docs/vector-map-inside-area-filter.md +++ b/sensing/pointcloud_preprocessor/docs/vector-map-inside-area-filter.md @@ -19,10 +19,10 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, so please ### Input -| Name | Type | Description | -| -------------------- | -------------------------------------------- | ------------------------------------ | -| `~/input` | `sensor_msgs::msg::PointCloud2` | input points | -| `~/input/vector_map` | `autoware_auto_mapping_msgs::msg::HADMapBin` | vector map used for filtering points | +| Name | Type | Description | +| -------------------- | --------------------------------------- | ------------------------------------ | +| `~/input` | `sensor_msgs::msg::PointCloud2` | input points | +| `~/input/vector_map` | `autoware_map_msgs::msg::LaneletMapBin` | vector map used for filtering points | ### Output diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp index ed0d753a68ecc..42078922d39b9 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp @@ -20,7 +20,7 @@ #include #include -#include +#include #include #include @@ -59,7 +59,7 @@ class Lanelet2MapFilterComponent : public rclcpp::Node std::shared_ptr tf_buffer_; std::shared_ptr tf_listener_; - rclcpp::Subscription::SharedPtr map_sub_; + rclcpp::Subscription::SharedPtr map_sub_; rclcpp::Subscription::SharedPtr pointcloud_sub_; rclcpp::Publisher::SharedPtr filtered_pointcloud_pub_; @@ -71,7 +71,7 @@ class Lanelet2MapFilterComponent : public rclcpp::Node void pointcloudCallback(const PointCloud2ConstPtr msg); - void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg); + void mapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg); bool transformPointCloud( const std::string & in_target_frame, const PointCloud2ConstPtr & in_cloud_ptr, diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp index 74209c1a22e4c..894768d385438 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter.hpp @@ -36,10 +36,10 @@ class VectorMapInsideAreaFilterComponent : public pointcloud_preprocessor::Filte void filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; - rclcpp::Subscription::SharedPtr map_sub_; + rclcpp::Subscription::SharedPtr map_sub_; lanelet::ConstPolygons3d polygon_lanelets_; - void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg); + void mapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg); // parameter std::string polygon_type_; diff --git a/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp index 502c85d1746e8..8f7cb2abec6a4 100644 --- a/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp @@ -51,7 +51,7 @@ Lanelet2MapFilterComponent::Lanelet2MapFilterComponent(const rclcpp::NodeOptions // Set subscriber { - map_sub_ = this->create_subscription( + map_sub_ = this->create_subscription( "input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&Lanelet2MapFilterComponent::mapCallback, this, _1)); pointcloud_sub_ = this->create_subscription( @@ -259,7 +259,7 @@ void Lanelet2MapFilterComponent::pointcloudCallback(const PointCloud2ConstPtr cl } void Lanelet2MapFilterComponent::mapCallback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr map_msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr map_msg) { lanelet_map_ptr_ = std::make_shared(); lanelet::utils::conversion::fromBinMsg(*map_msg, lanelet_map_ptr_); diff --git a/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp b/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp index 5b8755714b375..8fcf15326829f 100644 --- a/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp +++ b/sensing/pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter.cpp @@ -71,7 +71,7 @@ VectorMapInsideAreaFilterComponent::VectorMapInsideAreaFilterComponent( using std::placeholders::_1; // Set subscriber - map_sub_ = this->create_subscription( + map_sub_ = this->create_subscription( "input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&VectorMapInsideAreaFilterComponent::mapCallback, this, _1)); } @@ -107,7 +107,7 @@ void VectorMapInsideAreaFilterComponent::filter( } void VectorMapInsideAreaFilterComponent::mapCallback( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr map_msg) + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr map_msg) { tf_input_frame_ = map_msg->header.frame_id; diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index b0df04285ac9f..d02ea8e8cf14d 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -22,7 +22,6 @@ #include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp" #include "autoware_auto_geometry_msgs/msg/complex32.hpp" -#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" #include "autoware_auto_planning_msgs/msg/trajectory.hpp" #include "autoware_auto_vehicle_msgs/msg/control_mode_command.hpp" #include "autoware_auto_vehicle_msgs/msg/control_mode_report.hpp" @@ -37,6 +36,7 @@ #include "autoware_auto_vehicle_msgs/msg/vehicle_control_command.hpp" #include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp" #include "autoware_auto_vehicle_msgs/srv/control_mode_command.hpp" +#include "autoware_map_msgs/msg/lanelet_map_bin.hpp" #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include "geometry_msgs/msg/pose.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" @@ -64,7 +64,6 @@ namespace simple_planning_simulator using autoware_auto_control_msgs::msg::AckermannControlCommand; using autoware_auto_geometry_msgs::msg::Complex32; -using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_vehicle_msgs::msg::ControlModeReport; using autoware_auto_vehicle_msgs::msg::Engage; @@ -78,6 +77,7 @@ using autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport; using autoware_auto_vehicle_msgs::msg::VehicleControlCommand; using autoware_auto_vehicle_msgs::msg::VelocityReport; using autoware_auto_vehicle_msgs::srv::ControlModeCommand; +using autoware_map_msgs::msg::LaneletMapBin; using geometry_msgs::msg::AccelWithCovarianceStamped; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; @@ -146,7 +146,7 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_vehicle_cmd_; rclcpp::Subscription::SharedPtr sub_ackermann_cmd_; rclcpp::Subscription::SharedPtr sub_manual_ackermann_cmd_; - rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_map_; rclcpp::Subscription::SharedPtr sub_init_pose_; rclcpp::Subscription::SharedPtr sub_init_twist_; rclcpp::Subscription::SharedPtr sub_trajectory_; @@ -236,7 +236,7 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node /** * @brief subscribe lanelet map */ - void on_map(const HADMapBin::ConstSharedPtr msg); + void on_map(const LaneletMapBin::ConstSharedPtr msg); /** * @brief set initial pose for simulation with received message diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index 5652be138b18f..8cd74ec6561c0 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -12,10 +12,10 @@ autoware_cmake autoware_auto_control_msgs - autoware_auto_mapping_msgs autoware_auto_planning_msgs autoware_auto_tf2 autoware_auto_vehicle_msgs + autoware_map_msgs geometry_msgs lanelet2_core lanelet2_extension diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index a3715a1efe8ab..50e3b7004c72b 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -108,7 +108,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt using std::placeholders::_1; using std::placeholders::_2; - sub_map_ = create_subscription( + sub_map_ = create_subscription( "input/vector_map", rclcpp::QoS(10).transient_local(), std::bind(&SimplePlanningSimulator::on_map, this, _1)); sub_init_pose_ = create_subscription( @@ -384,7 +384,7 @@ void SimplePlanningSimulator::on_timer() publish_tf(current_odometry_); } -void SimplePlanningSimulator::on_map(const HADMapBin::ConstSharedPtr msg) +void SimplePlanningSimulator::on_map(const LaneletMapBin::ConstSharedPtr msg) { auto lanelet_map_ptr = std::make_shared(); diff --git a/tools/simulator_test/simulator_compatibility_test/package.xml b/tools/simulator_test/simulator_compatibility_test/package.xml index d0ed3e69b9c30..e37093f4b36b0 100644 --- a/tools/simulator_test/simulator_compatibility_test/package.xml +++ b/tools/simulator_test/simulator_compatibility_test/package.xml @@ -11,12 +11,12 @@ autoware_auto_control_msgs autoware_auto_geometry_msgs - autoware_auto_mapping_msgs autoware_auto_msgs autoware_auto_perception_msgs autoware_auto_planning_msgs autoware_auto_system_msgs autoware_auto_vehicle_msgs + autoware_map_msgs rclpy ament_copyright