Skip to content

Commit

Permalink
feat!: replace autoware_auto_msgs with autoware_msgs for sensing modu…
Browse files Browse the repository at this point in the history
…les (autowarefoundation#7247)

Signed-off-by: Ryohsuke Mitsudome <[email protected]>
Co-authored-by: Cynthia Liu <[email protected]>
Co-authored-by: NorahXiong <[email protected]>
Co-authored-by: beginningfan <[email protected]>
  • Loading branch information
4 people authored and a-maumau committed Jun 7, 2024
1 parent 22e3257 commit ca8ca2f
Show file tree
Hide file tree
Showing 11 changed files with 29 additions and 30 deletions.
8 changes: 4 additions & 4 deletions sensing/pointcloud_preprocessor/docs/vector-map-filter.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>

#include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
#include <autoware_vehicle_msgs/msg/velocity_report.hpp>
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand Down Expand Up @@ -127,7 +127,7 @@ class PointCloudConcatenationComponent : public rclcpp::Node
/** \brief A vector of subscriber. */
std::vector<rclcpp::Subscription<PointCloud2>::SharedPtr> filters_;

rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::VelocityReport>::SharedPtr sub_twist_;
rclcpp::Subscription<autoware_vehicle_msgs::msg::VelocityReport>::SharedPtr sub_twist_;

rclcpp::TimerBase::SharedPtr timer_;
diagnostic_updater::Updater updater_{this};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

#include <pcl/common/centroid.h>
Expand Down Expand Up @@ -59,7 +59,7 @@ class Lanelet2MapFilterComponent : public rclcpp::Node
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;

rclcpp::Subscription<autoware_auto_mapping_msgs::msg::HADMapBin>::SharedPtr map_sub_;
rclcpp::Subscription<autoware_map_msgs::msg::LaneletMapBin>::SharedPtr map_sub_;
rclcpp::Subscription<PointCloud2>::SharedPtr pointcloud_sub_;
rclcpp::Publisher<PointCloud2>::SharedPtr filtered_pointcloud_pub_;

Expand All @@ -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,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,10 @@ class VectorMapInsideAreaFilterComponent : public pointcloud_preprocessor::Filte
void filter(
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override;

rclcpp::Subscription<autoware_auto_mapping_msgs::msg::HADMapBin>::SharedPtr map_sub_;
rclcpp::Subscription<autoware_map_msgs::msg::LaneletMapBin>::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_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ Lanelet2MapFilterComponent::Lanelet2MapFilterComponent(const rclcpp::NodeOptions

// Set subscriber
{
map_sub_ = this->create_subscription<autoware_auto_mapping_msgs::msg::HADMapBin>(
map_sub_ = this->create_subscription<autoware_map_msgs::msg::LaneletMapBin>(
"input/vector_map", rclcpp::QoS{1}.transient_local(),
std::bind(&Lanelet2MapFilterComponent::mapCallback, this, _1));
pointcloud_sub_ = this->create_subscription<PointCloud2>(
Expand Down Expand Up @@ -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::LaneletMap>();
lanelet::utils::conversion::fromBinMsg(*map_msg, lanelet_map_ptr_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ VectorMapInsideAreaFilterComponent::VectorMapInsideAreaFilterComponent(

using std::placeholders::_1;
// Set subscriber
map_sub_ = this->create_subscription<autoware_auto_mapping_msgs::msg::HADMapBin>(
map_sub_ = this->create_subscription<autoware_map_msgs::msg::LaneletMapBin>(
"input/vector_map", rclcpp::QoS{1}.transient_local(),
std::bind(&VectorMapInsideAreaFilterComponent::mapCallback, this, _1));
}
Expand Down Expand Up @@ -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;

Expand Down
8 changes: 4 additions & 4 deletions sensing/vehicle_velocity_converter/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,15 @@

## Purpose

This package converts autoware_auto_vehicle_msgs::msg::VehicleReport message to geometry_msgs::msg::TwistWithCovarianceStamped for gyro odometer node.
This package converts autoware_vehicle_msgs::msg::VehicleReport message to geometry_msgs::msg::TwistWithCovarianceStamped for gyro odometer node.

## Inputs / Outputs

### Input

| Name | Type | Description |
| ----------------- | ------------------------------------------------ | ---------------- |
| `velocity_status` | `autoware_auto_vehicle_msgs::msg::VehicleReport` | vehicle velocity |
| Name | Type | Description |
| ----------------- | ------------------------------------------- | ---------------- |
| `velocity_status` | `autoware_vehicle_msgs::msg::VehicleReport` | vehicle velocity |

### Output

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_vehicle_msgs/msg/velocity_report.hpp"
#include "autoware_vehicle_msgs/msg/velocity_report.hpp"
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>

Expand All @@ -32,10 +32,9 @@ class VehicleVelocityConverter : public rclcpp::Node
~VehicleVelocityConverter() = default;

private:
void callbackVelocityReport(const autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr msg);
void callbackVelocityReport(const autoware_vehicle_msgs::msg::VelocityReport::SharedPtr msg);

rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::VelocityReport>::SharedPtr
vehicle_report_sub_;
rclcpp::Subscription<autoware_vehicle_msgs::msg::VelocityReport>::SharedPtr vehicle_report_sub_;

rclcpp::Publisher<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr
twist_with_covariance_pub_;
Expand Down
2 changes: 1 addition & 1 deletion sensing/vehicle_velocity_converter/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_vehicle_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ VehicleVelocityConverter::VehicleVelocityConverter() : Node("vehicle_velocity_co
frame_id_ = declare_parameter<std::string>("frame_id");
speed_scale_factor_ = declare_parameter<double>("speed_scale_factor");

vehicle_report_sub_ = create_subscription<autoware_auto_vehicle_msgs::msg::VelocityReport>(
vehicle_report_sub_ = create_subscription<autoware_vehicle_msgs::msg::VelocityReport>(
"velocity_status", rclcpp::QoS{100},
std::bind(&VehicleVelocityConverter::callbackVelocityReport, this, std::placeholders::_1));

Expand All @@ -31,7 +31,7 @@ VehicleVelocityConverter::VehicleVelocityConverter() : Node("vehicle_velocity_co
}

void VehicleVelocityConverter::callbackVelocityReport(
const autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr msg)
const autoware_vehicle_msgs::msg::VelocityReport::SharedPtr msg)
{
if (msg->header.frame_id != frame_id_) {
RCLCPP_WARN(get_logger(), "frame_id is not base_link.");
Expand Down

0 comments on commit ca8ca2f

Please sign in to comment.