Skip to content

Commit

Permalink
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil…
Browse files Browse the repository at this point in the history
…es sensing/autoware_pointcloud_preprocessor

Signed-off-by: vish0012 <[email protected]>
  • Loading branch information
vish0012 committed Jan 15, 2025
1 parent 1586372 commit 97aaeb2
Show file tree
Hide file tree
Showing 18 changed files with 64 additions and 61 deletions.
20 changes: 10 additions & 10 deletions sensing/autoware_pointcloud_preprocessor/docs/blockage-diag.md
Original file line number Diff line number Diff line change
Expand Up @@ -38,16 +38,16 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class,

### Output

| Name | Type | Description |
| :-------------------------------------------------------- | :-------------------------------------- | ------------------------------------------------------------------------------------------------ |
| `~/output/blockage_diag/debug/blockage_mask_image` | `sensor_msgs::msg::Image` | The mask image of detected blockage |
| `~/output/blockage_diag/debug/ground_blockage_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in ground region |
| `~/output/blockage_diag/debug/sky_blockage_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in sky region |
| `~/output/blockage_diag/debug/lidar_depth_map` | `sensor_msgs::msg::Image` | The depth map image of input point cloud |
| `~/output/blockage_diag/debug/single_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of detected dusty area in latest single frame |
| `~/output/blockage_diag/debug/multi_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of continuous detected dusty area |
| `~/output/blockage_diag/debug/blockage_dust_merged_image` | `sensor_msgs::msg::Image` | The merged image of blockage detection(red) and multi frame dusty area detection(yellow) results |
| `~/output/blockage_diag/debug/ground_dust_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The ratio of dusty area divided by area where ray usually returns from the ground. |
| Name | Type | Description |
| :-------------------------------------------------------- | :-------------------------------------------------- | ------------------------------------------------------------------------------------------------ |
| `~/output/blockage_diag/debug/blockage_mask_image` | `sensor_msgs::msg::Image` | The mask image of detected blockage |
| `~/output/blockage_diag/debug/ground_blockage_ratio` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in ground region |
| `~/output/blockage_diag/debug/sky_blockage_ratio` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in sky region |
| `~/output/blockage_diag/debug/lidar_depth_map` | `sensor_msgs::msg::Image` | The depth map image of input point cloud |
| `~/output/blockage_diag/debug/single_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of detected dusty area in latest single frame |
| `~/output/blockage_diag/debug/multi_frame_dust_mask` | `sensor_msgs::msg::Image` | The mask image of continuous detected dusty area |
| `~/output/blockage_diag/debug/blockage_dust_merged_image` | `sensor_msgs::msg::Image` | The merged image of blockage detection(red) and multi frame dusty area detection(yellow) results |
| `~/output/blockage_diag/debug/ground_dust_ratio` | `autoware_internal_debug_msgs::msg::Float32Stamped` | The ratio of dusty area divided by area where ray usually returns from the ground. |

## Parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,11 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class,

### Output

| Name | Type | Description |
| ---------------------------------------------- | --------------------------------------- | ------------------------------------------------------- |
| `/dual_return_outlier_filter/frequency_image` | `sensor_msgs::msg::Image` | The histogram image that represent visibility |
| `/dual_return_outlier_filter/visibility` | `tier4_debug_msgs::msg::Float32Stamped` | A representation of visibility with a value from 0 to 1 |
| `/dual_return_outlier_filter/pointcloud_noise` | `sensor_msgs::msg::Pointcloud2` | The pointcloud removed as noise |
| Name | Type | Description |
| ---------------------------------------------- | --------------------------------------------------- | ------------------------------------------------------- |
| `/dual_return_outlier_filter/frequency_image` | `sensor_msgs::msg::Image` | The histogram image that represent visibility |
| `/dual_return_outlier_filter/visibility` | `autoware_internal_debug_msgs::msg::Float32Stamped` | A representation of visibility with a value from 0 to 1 |
| `/dual_return_outlier_filter/pointcloud_noise` | `sensor_msgs::msg::Pointcloud2` | The pointcloud removed as noise |

## Parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,10 @@
#include <opencv2/highgui/highgui.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float32_stamped.hpp>
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/header.hpp>
#include <tier4_debug_msgs/msg/float32_stamped.hpp>

#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp>
Expand Down Expand Up @@ -58,10 +58,13 @@ class BlockageDiagComponent : public autoware::pointcloud_preprocessor::Filter
image_transport::Publisher single_frame_dust_mask_pub;
image_transport::Publisher multi_frame_dust_mask_pub;
image_transport::Publisher blockage_dust_merged_pub;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr ground_blockage_ratio_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr sky_blockage_ratio_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr ground_dust_ratio_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::StringStamped>::SharedPtr blockage_type_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32Stamped>::SharedPtr
ground_blockage_ratio_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32Stamped>::SharedPtr
sky_blockage_ratio_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32Stamped>::SharedPtr
ground_dust_ratio_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::StringStamped>::SharedPtr blockage_type_pub_;

private:
void onBlockageChecker(DiagnosticStatusWrapper & stat);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,14 +69,14 @@
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>

#include <autoware_internal_debug_msgs/msg/int32_stamped.hpp>
#include <autoware_internal_debug_msgs/msg/string_stamped.hpp>
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tier4_debug_msgs/msg/int32_stamped.hpp>
#include <tier4_debug_msgs/msg/string_stamped.hpp>

#include <message_filters/pass_through.h>
#include <message_filters/subscriber.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,13 +68,13 @@
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>

#include <autoware_internal_debug_msgs/msg/int32_stamped.hpp>
#include <autoware_internal_debug_msgs/msg/string_stamped.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>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tier4_debug_msgs/msg/int32_stamped.hpp>
#include <tier4_debug_msgs/msg/string_stamped.hpp>

#include <message_filters/pass_through.h>
#include <message_filters/subscriber.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,9 @@
#include <opencv2/highgui/highgui.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float32_stamped.hpp>
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_debug_msgs/msg/float32_stamped.hpp>

#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp>
Expand Down Expand Up @@ -54,7 +54,7 @@ class DualReturnOutlierFilterComponent : public autoware::pointcloud_preprocesso
/** \brief Parameter service callback */
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);
image_transport::Publisher image_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr visibility_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32Stamped>::SharedPtr visibility_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr noise_cloud_pub_;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class RingOutlierFilterComponent : public autoware::pointcloud_preprocessor::Fil
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output,
const TransformInfo & transform_info) override;

rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr visibility_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32Stamped>::SharedPtr visibility_pub_;

private:
/** \brief publisher of excluded pointcloud for debug reason. **/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,14 +68,14 @@
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>

#include <autoware_internal_debug_msgs/msg/int32_stamped.hpp>
#include <autoware_internal_debug_msgs/msg/string_stamped.hpp>
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tier4_debug_msgs/msg/int32_stamped.hpp>
#include <tier4_debug_msgs/msg/string_stamped.hpp>

#include <message_filters/pass_through.h>
#include <message_filters/subscriber.h>
Expand Down
2 changes: 1 addition & 1 deletion sensing/autoware_pointcloud_preprocessor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_pcl_extensions</depend>
<depend>autoware_point_types</depend>
Expand All @@ -51,7 +52,6 @@
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_debug_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options
std::string(this->get_namespace()) + ": dust_validation", this,
&BlockageDiagComponent::dustChecker);

ground_dust_ratio_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
ground_dust_ratio_pub_ = create_publisher<autoware_internal_debug_msgs::msg::Float32Stamped>(
"blockage_diag/debug/ground_dust_ratio", rclcpp::SensorDataQoS());
if (publish_debug_image_) {
single_frame_dust_mask_pub =
Expand All @@ -86,9 +86,9 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options
blockage_mask_pub_ =
image_transport::create_publisher(this, "blockage_diag/debug/blockage_mask_image");
}
ground_blockage_ratio_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
ground_blockage_ratio_pub_ = create_publisher<autoware_internal_debug_msgs::msg::Float32Stamped>(
"blockage_diag/debug/ground_blockage_ratio", rclcpp::SensorDataQoS());
sky_blockage_ratio_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
sky_blockage_ratio_pub_ = create_publisher<autoware_internal_debug_msgs::msg::Float32Stamped>(
"blockage_diag/debug/sky_blockage_ratio", rclcpp::SensorDataQoS());
using std::placeholders::_1;
set_param_res_ = this->add_on_set_parameters_callback(
Expand Down Expand Up @@ -315,7 +315,7 @@ void BlockageDiagComponent::filter(
cv::Mat ground_mask(cv::Size(ideal_horizontal_bins, horizontal_ring_id_), CV_8UC1);
cv::vconcat(sky_blank, single_dust_ground_img, single_dust_img);

tier4_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg;
autoware_internal_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg;
ground_dust_ratio_ = static_cast<float>(cv::countNonZero(single_dust_ground_img)) /
(single_dust_ground_img.cols * single_dust_ground_img.rows);
ground_dust_ratio_msg.data = ground_dust_ratio_;
Expand Down Expand Up @@ -386,12 +386,12 @@ void BlockageDiagComponent::filter(
}
}

tier4_debug_msgs::msg::Float32Stamped ground_blockage_ratio_msg;
autoware_internal_debug_msgs::msg::Float32Stamped ground_blockage_ratio_msg;
ground_blockage_ratio_msg.data = ground_blockage_ratio_;
ground_blockage_ratio_msg.stamp = now();
ground_blockage_ratio_pub_->publish(ground_blockage_ratio_msg);

tier4_debug_msgs::msg::Float32Stamped sky_blockage_ratio_msg;
autoware_internal_debug_msgs::msg::Float32Stamped sky_blockage_ratio_msg;
sky_blockage_ratio_msg.data = sky_blockage_ratio_;
sky_blockage_ratio_msg.stamp = now();
sky_blockage_ratio_pub_->publish(sky_blockage_ratio_msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -455,9 +455,9 @@ void PointCloudConcatenateDataSynchronizerComponent::publish()
if (debug_publisher_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
}
for (const auto & e : cloud_stdmap_) {
Expand All @@ -468,7 +468,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publish()
std::chrono::nanoseconds(
(this->get_clock()->now() - e.second->header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -271,7 +271,7 @@ void PointCloudConcatenationComponent::publish()
std::chrono::nanoseconds(
(this->get_clock()->now() - e.second->header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms);
}
}
Expand All @@ -297,9 +297,9 @@ void PointCloudConcatenationComponent::publish()
if (debug_publisher_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -194,17 +194,17 @@ void CropBoxFilterComponent::faster_filter(
if (debug_publisher_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);

auto pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds()))
.count();

debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ void DistortionCorrectorComponent::pointcloud_callback(PointCloud2::UniquePtr po
std::chrono::nanoseconds(
(this->get_clock()->now() - pointcloud_msg->header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
}

Expand All @@ -133,9 +133,9 @@ void DistortionCorrectorComponent::pointcloud_callback(PointCloud2::UniquePtr po
if (debug_publisher_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,17 +142,17 @@ void PickupBasedVoxelGridDownsampleFilterComponent::filter(
if (debug_publisher_) {
const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true);
const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/cyclic_time_ms", cyclic_time_ms);
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);

auto pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds()))
.count();

debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
debug_publisher_->publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/pipeline_latency_ms", pipeline_latency_ms);
}
}
Expand Down
Loading

0 comments on commit 97aaeb2

Please sign in to comment.