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