Skip to content

Commit

Permalink
feat(autoware.universe): replace autoware_auto_mapping_msg with autow…
Browse files Browse the repository at this point in the history
…are_map_msg (#5615)

* feat(autoware.universe): replace autoware_auto_mapping_msg with autoware_map_msg

Signed-off-by: liu cui <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: liu cui <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
cyn-liu and pre-commit-ci[bot] authored Nov 22, 2023
1 parent b5d6c51 commit 6137908
Show file tree
Hide file tree
Showing 117 changed files with 273 additions and 276 deletions.
2 changes: 1 addition & 1 deletion common/tier4_traffic_light_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_auto_mapping_msgs</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>lanelet2_extension</depend>
<depend>libqt5-core</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ void TrafficLightPublishPanel::onInitialize()
pub_traffic_signals_ = raw_node_->create_publisher<TrafficSignalArray>(
"/perception/traffic_light_recognition/traffic_signals", rclcpp::QoS(1));

sub_vector_map_ = raw_node_->create_subscription<HADMapBin>(
sub_vector_map_ = raw_node_->create_subscription<LaneletMapBin>(
"/map/vector_map", rclcpp::QoS{1}.transient_local(),
std::bind(&TrafficLightPublishPanel::onVectorMap, this, _1));
createWallTimer();
Expand Down Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <rclcpp/timer.hpp>
#include <rviz_common/panel.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_perception_msgs/msg/traffic_signal_array.hpp>
#endif

Expand All @@ -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;
Expand All @@ -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<TrafficSignalArray>::SharedPtr pub_traffic_signals_;
rclcpp::Subscription<HADMapBin>::SharedPtr sub_vector_map_;
rclcpp::Subscription<LaneletMapBin>::SharedPtr sub_vector_map_;

QSpinBox * publishing_rate_input_;
QComboBox * traffic_light_id_input_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_auto_mapping_msgs</depend>
<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_map_msgs</depend>
<depend>geometry_msgs</depend>
<depend>lanelet2_extension</depend>
<depend>rclcpp</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ TrafficLightRecognitionMarkerPublisher::TrafficLightRecognitionMarkerPublisher(
{
using std::placeholders::_1;

sub_map_ptr_ = this->create_subscription<autoware_auto_mapping_msgs::msg::HADMapBin>(
sub_map_ptr_ = this->create_subscription<autoware_map_msgs::msg::LaneletMapBin>(
"~/input/lanelet2_map", rclcpp::QoS{1}.transient_local(),
std::bind(&TrafficLightRecognitionMarkerPublisher::onMap, this, _1));
sub_tlr_ptr_ = this->create_subscription<autoware_auto_perception_msgs::msg::TrafficSignalArray>(
Expand All @@ -36,7 +36,7 @@ TrafficLightRecognitionMarkerPublisher::TrafficLightRecognitionMarkerPublisher(
this->create_publisher<visualization_msgs::msg::MarkerArray>("~/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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@
#include <lanelet2_extension/visualization/visualization.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_perception_msgs/msg/traffic_signal_array.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

Expand All @@ -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;
Expand All @@ -41,12 +41,12 @@ class TrafficLightRecognitionMarkerPublisher : public rclcpp::Node
explicit TrafficLightRecognitionMarkerPublisher(const rclcpp::NodeOptions & options);

private:
rclcpp::Subscription<HADMapBin>::SharedPtr sub_map_ptr_;
rclcpp::Subscription<LaneletMapBin>::SharedPtr sub_map_ptr_;
rclcpp::Subscription<autoware_auto_perception_msgs::msg::TrafficSignalArray>::SharedPtr
sub_tlr_ptr_;
rclcpp::Publisher<MarkerArray>::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);
Expand Down
2 changes: 1 addition & 1 deletion control/lane_departure_checker/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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`]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/ros/processing_time_publisher.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
Expand All @@ -42,7 +42,7 @@

namespace lane_departure_checker
{
using autoware_auto_mapping_msgs::msg::HADMapBin;
using autoware_map_msgs::msg::LaneletMapBin;

struct NodeParam
{
Expand All @@ -67,7 +67,7 @@ class LaneDepartureCheckerNode : public rclcpp::Node
private:
// Subscriber
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
rclcpp::Subscription<HADMapBin>::SharedPtr sub_lanelet_map_bin_;
rclcpp::Subscription<LaneletMapBin>::SharedPtr sub_lanelet_map_bin_;
rclcpp::Subscription<LaneletRoute>::SharedPtr sub_route_;
rclcpp::Subscription<Trajectory>::SharedPtr sub_reference_trajectory_;
rclcpp::Subscription<Trajectory>::SharedPtr sub_predicted_trajectory_;
Expand All @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion control/lane_departure_checker/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_auto_mapping_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>boost</depend>
<depend>diagnostic_updater</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o
// Subscriber
sub_odom_ = this->create_subscription<nav_msgs::msg::Odometry>(
"~/input/odometry", 1, std::bind(&LaneDepartureCheckerNode::onOdometry, this, _1));
sub_lanelet_map_bin_ = this->create_subscription<HADMapBin>(
sub_lanelet_map_bin_ = this->create_subscription<LaneletMapBin>(
"~/input/lanelet_map_bin", rclcpp::QoS{1}.transient_local(),
std::bind(&LaneDepartureCheckerNode::onLaneletMapBin, this, _1));
sub_route_ = this->create_subscription<LaneletRoute>(
Expand Down Expand Up @@ -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::LaneletMap>();
lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_, &traffic_rules_, &routing_graph_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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. |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ bool ArTagBasedLocalizer::setup()
/*
Subscribers
*/
map_bin_sub_ = this->create_subscription<HADMapBin>(
map_bin_sub_ = this->create_subscription<LaneletMapBin>(
"~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal),
std::bind(&ArTagBasedLocalizer::map_bin_callback, this, std::placeholders::_1));

Expand Down Expand Up @@ -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<landmark_manager::Landmark> landmarks =
landmark_manager::parse_landmarks(msg, "apriltag_16h5", this->get_logger());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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);
Expand All @@ -105,7 +105,7 @@ class ArTagBasedLocalizer : public rclcpp::Node
std::unique_ptr<image_transport::ImageTransport> it_;

// Subscribers
rclcpp::Subscription<HADMapBin>::SharedPtr map_bin_sub_;
rclcpp::Subscription<LaneletMapBin>::SharedPtr map_bin_sub_;
rclcpp::Subscription<Image>::SharedPtr image_sub_;
rclcpp::Subscription<CameraInfo>::SharedPtr cam_info_sub_;
rclcpp::Subscription<PoseWithCovarianceStamped>::SharedPtr ekf_pose_sub_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include <rclcpp/rclcpp.hpp>

#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp"
#include "autoware_map_msgs/msg/lanelet_map_bin.hpp"
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <visualization_msgs/msg/marker_array.hpp>
Expand All @@ -35,7 +35,7 @@ struct Landmark
};

std::vector<Landmark> 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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

<build_depend>eigen</build_depend>

<depend>autoware_auto_mapping_msgs</depend>
<depend>autoware_map_msgs</depend>
<depend>geometry_msgs</depend>
<depend>lanelet2_extension</depend>
<depend>rclcpp</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,12 @@ namespace landmark_manager
{

std::vector<Landmark> 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::LaneletMap>()};
lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr);
Expand Down
14 changes: 7 additions & 7 deletions localization/yabloc/yabloc_common/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include <signal_processing/lowpass_filter_1d.hpp>
#include <yabloc_common/ground_plane.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand All @@ -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;
Expand All @@ -65,7 +65,7 @@ class GroundServer : public rclcpp::Node
const int K;

// Subscriber
rclcpp::Subscription<HADMapBin>::SharedPtr sub_map_;
rclcpp::Subscription<LaneletMapBin>::SharedPtr sub_map_;
rclcpp::Subscription<PoseStamped>::SharedPtr sub_pose_stamped_;
rclcpp::Subscription<PoseCovStamped>::SharedPtr sub_initial_pose_;
// Publisher
Expand All @@ -86,7 +86,7 @@ class GroundServer : public rclcpp::Node
std::vector<int> 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);

Expand Down
Loading

0 comments on commit 6137908

Please sign in to comment.