diff --git a/modules/perception/lidar/lib/detector/graph_segmentation/graph_segmentation.cc b/modules/perception/lidar/lib/detector/graph_segmentation/graph_segmentation.cc index e81152e1..b4c9d7c3 100644 --- a/modules/perception/lidar/lib/detector/graph_segmentation/graph_segmentation.cc +++ b/modules/perception/lidar/lib/detector/graph_segmentation/graph_segmentation.cc @@ -69,6 +69,19 @@ bool GraphClusterSegmenter::Init(const StageConfig& stage_config) { // clear background objects bg_objects_.clear(); + // Print actual loaded configuration for debugging + AINFO << "========== GraphClusterSegmenter Actual Config =========="; + AINFO << "resolution: " << resolution_; + AINFO << "threshold: " << threshold_; + AINFO << "min_pt_number: " << min_pt_number_; + AINFO << "search_radius: " << search_radius_; + AINFO << "height_threshold: " << height_threshold_; + AINFO << "z_min_from_ground: " << stage_conf_.graph_cluster_segmenter_config().z_min_from_ground(); + AINFO << "min_radius: " << stage_conf_.graph_cluster_segmenter_config().min_radius(); + AINFO << "grid_width: " << grid_width_; + AINFO << "grid_height: " << grid_height_; + AINFO << "=========================================================="; + // Fall back to default Init without external config path. LidarDetectorInitOptions init_options; return Init(init_options); diff --git a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc index 59ce2d5a..6b44d0dd 100644 --- a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc +++ b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc @@ -19,12 +19,19 @@ #include #include #include +#include +#include +#include #include "cyber/common/file.h" #include "modules/perception/common/point_cloud_processing/common.h" #include "modules/perception/lib/config_manager/config_manager.h" #include "modules/perception/lidar/common/lidar_log.h" #include "modules/perception/lidar/common/lidar_point_label.h" +#include "modules/perception/lidar/common/pcl_util.h" +#include +#include +#include namespace apollo { namespace perception { @@ -87,6 +94,34 @@ bool SpatioTemporalGroundDetector::InitInternal( << debug_cloud_channel_; } + // Load PCD save settings + enable_save_ground_pcd_ = config.enable_save_ground_pcd(); + ground_pcd_save_dir_ = config.ground_pcd_save_dir(); + + // Check environment variable override (GROUND_PCD_SAVE_DIR) + // Environment variable takes precedence over config file + const char* env_save_dir = std::getenv("GROUND_PCD_SAVE_DIR"); + if (env_save_dir != nullptr && strlen(env_save_dir) > 0) { + ground_pcd_save_dir_ = std::string(env_save_dir); + AINFO << "GROUND_PCD_SAVE_DIR environment variable set, using: " + << ground_pcd_save_dir_; + } + + if (enable_save_ground_pcd_) { + // Create directory if it doesn't exist + if (!cyber::common::DirectoryExists(ground_pcd_save_dir_)) { + if (cyber::common::EnsureDirectory(ground_pcd_save_dir_)) { + AINFO << "Created ground PCD save directory: " << ground_pcd_save_dir_; + } else { + AWARN << "Failed to create ground PCD save directory: " + << ground_pcd_save_dir_ << ", PCD saving disabled"; + enable_save_ground_pcd_ = false; + } + } else { + AINFO << "Ground PCD save enabled, saving to: " << ground_pcd_save_dir_; + } + } + // 2. Setup Algorithm Parameters // Using make_unique for exception safety (though Apollo doesn't use // exceptions much) @@ -137,6 +172,21 @@ bool SpatioTemporalGroundDetector::InitInternal( ground_service_content_.Init(config.roi_rad_x(), config.roi_rad_y(), coarse_grid, coarse_grid); + + // Print actual loaded configuration for debugging + AINFO << "========== SpatioTemporalGroundDetector Actual Config =========="; + AINFO << "ground_thres: " << ground_thres_; + AINFO << "near_range_ground_thres: " << near_range_ground_thres_; + AINFO << "middle_range_ground_thres: " << middle_range_ground_thres_; + AINFO << "near_range_dist: " << near_range_dist_; + AINFO << "middle_range_dist: " << middle_range_dist_; + AINFO << "small_grid_size: " << coarse_grid; + AINFO << "big_grid_size: " << param_->nr_grids_fine; + AINFO << "planefit_orien_threshold: " << param_->planefit_orien_threshold; + AINFO << "planefit_dist_threshold_near: " << param_->planefit_dist_threshold_near; + AINFO << "planefit_dist_threshold_far: " << param_->planefit_dist_threshold_far; + AINFO << "=============================================================="; + return true; } @@ -185,6 +235,177 @@ void SpatioTemporalGroundDetector::PublishDebugCloud( debug_writer_->Write(msg); } +void SpatioTemporalGroundDetector::SaveGroundPcd(const LidarFrame& frame, + const std::vector& ground_indices, + const std::vector& non_ground_indices, + const std::vector* processed_indices) { + if (!enable_save_ground_pcd_) { + return; // Not enabled + } + + const std::string& save_dir = ground_pcd_save_dir_; + + const auto& points = frame.world_cloud->points(); + + // Find max index for validation + int max_ground_idx = ground_indices.empty() ? -1 : *std::max_element(ground_indices.begin(), ground_indices.end()); + int max_nonground_idx = non_ground_indices.empty() ? -1 : *std::max_element(non_ground_indices.begin(), non_ground_indices.end()); + + AINFO << "SaveGroundPcd: world_cloud_size=" << points.size() + << " processed_size=" << (processed_indices ? processed_indices->size() : 0) + << " ground_indices=" << ground_indices.size() << " max_idx=" << max_ground_idx + << " non_ground_indices=" << non_ground_indices.size() << " max_idx=" << max_nonground_idx; + + // Save FULL world cloud (for reference) + { + pcl::PointCloud full_cloud; + full_cloud.reserve(points.size()); + for (size_t i = 0; i < points.size(); ++i) { + const auto& pt = points[i]; + PCLPointXYZIT pcl_pt; + pcl_pt.x = static_cast(pt.x); + pcl_pt.y = static_cast(pt.y); + pcl_pt.z = static_cast(pt.z); + pcl_pt.intensity = static_cast(pt.intensity); + pcl_pt.timestamp = 0; + full_cloud.push_back(pcl_pt); + } + + char path[1024]; + std::snprintf(path, sizeof(path), "%s/%06u_input_full_%.6f.pcd", + save_dir, pcd_save_seq_num_, frame.timestamp); + pcl::PCDWriter writer; + writer.writeBinary(path, full_cloud); + AINFO << "Saved input_full cloud: " << path << " size=" << full_cloud.size(); + } + + // Save PROCESSED input points (actual input to ground detection - ROI filtered) + // This is what the web tool should use to match system results! + if (processed_indices && !processed_indices->empty()) { + pcl::PointCloud processed_cloud; + processed_cloud.reserve(processed_indices->size()); + + for (int idx : *processed_indices) { + if (idx >= 0 && static_cast(idx) < points.size()) { + const auto& pt = points[idx]; + PCLPointXYZIT pcl_pt; + pcl_pt.x = static_cast(pt.x); + pcl_pt.y = static_cast(pt.y); + pcl_pt.z = static_cast(pt.z); + pcl_pt.intensity = static_cast(pt.intensity); + pcl_pt.timestamp = 0; + processed_cloud.push_back(pcl_pt); + } + } + + char path[1024]; + std::snprintf(path, sizeof(path), "%s/%06u_input_%.6f.pcd", + save_dir, pcd_save_seq_num_, frame.timestamp); + pcl::PCDWriter writer; + writer.writeBinary(path, processed_cloud); + AINFO << "Saved input (processed/ROI-filtered) cloud: " << path << " size=" << processed_cloud.size(); + } else { + // No ROI filtering, input == input_full + AINFO << "No ROI filtering applied, input same as input_full"; + } + + // Save full cloud with ground/non-ground marked in intensity + { + pcl::PointCloud labeled_cloud; + labeled_cloud.reserve(points.size()); + + // Build ground index set for quick lookup + std::unordered_set ground_set(ground_indices.begin(), ground_indices.end()); + + for (size_t i = 0; i < points.size(); ++i) { + const auto& pt = points[i]; + PCLPointXYZIT pcl_pt; + pcl_pt.x = static_cast(pt.x); + pcl_pt.y = static_cast(pt.y); + pcl_pt.z = static_cast(pt.z); + // Mark ground as intensity=1, non-ground as intensity=255 + pcl_pt.intensity = (ground_set.find(static_cast(i)) != ground_set.end()) ? 1 : 255; + pcl_pt.timestamp = 0; + labeled_cloud.push_back(pcl_pt); + } + + char path[1024]; + std::snprintf(path, sizeof(path), "%s/%06u_labeled_%.6f.pcd", + save_dir, pcd_save_seq_num_, frame.timestamp); + pcl::PCDWriter writer; + writer.writeBinary(path, labeled_cloud); + AINFO << "Saved labeled cloud: " << path << " size=" << labeled_cloud.size(); + } + + // Save ground points only + if (!ground_indices.empty()) { + pcl::PointCloud ground_cloud; + ground_cloud.reserve(ground_indices.size()); + for (int idx : ground_indices) { + if (idx >= 0 && static_cast(idx) < points.size()) { + const auto& pt = points[idx]; + PCLPointXYZIT pcl_pt; + pcl_pt.x = static_cast(pt.x); + pcl_pt.y = static_cast(pt.y); + pcl_pt.z = static_cast(pt.z); + pcl_pt.intensity = static_cast(pt.intensity); + pcl_pt.timestamp = 0; + ground_cloud.push_back(pcl_pt); + } + } + + char path[1024]; + std::snprintf(path, sizeof(path), "%s/%06u_ground_%.6f.pcd", + save_dir, pcd_save_seq_num_, frame.timestamp); + pcl::PCDWriter writer; + writer.writeBinary(path, ground_cloud); + AINFO << "Saved ground: " << path << " size=" << ground_cloud.size(); + } + + // Save non-ground points only + if (!non_ground_indices.empty()) { + pcl::PointCloud nonground_cloud; + nonground_cloud.reserve(non_ground_indices.size()); + for (int idx : non_ground_indices) { + if (idx >= 0 && static_cast(idx) < points.size()) { + const auto& pt = points[idx]; + PCLPointXYZIT pcl_pt; + pcl_pt.x = static_cast(pt.x); + pcl_pt.y = static_cast(pt.y); + pcl_pt.z = static_cast(pt.z); + pcl_pt.intensity = static_cast(pt.intensity); + pcl_pt.timestamp = 0; + nonground_cloud.push_back(pcl_pt); + } + } + + char path[1024]; + std::snprintf(path, sizeof(path), "%s/%06u_nonground_%.6f.pcd", + save_dir, pcd_save_seq_num_, frame.timestamp); + pcl::PCDWriter writer; + writer.writeBinary(path, nonground_cloud); + AINFO << "Saved non-ground: " << path << " size=" << nonground_cloud.size(); + } + + // Save vehicle pose (lidar2world_pose translation) for ground_analyzer tool + { + char path[1024]; + std::snprintf(path, sizeof(path), "%s/%06u_vehicle_%.6f.txt", + save_dir, pcd_save_seq_num_, frame.timestamp); + std::ofstream pose_file(path); + pose_file << std::fixed << std::setprecision(6); + pose_file << "# Vehicle pose (lidar2world_pose translation) in world coordinates" << std::endl; + pose_file << "# Format: vehicle_x vehicle_y vehicle_z" << std::endl; + pose_file << frame.lidar2world_pose.translation().x() << " " + << frame.lidar2world_pose.translation().y() << " " + << frame.lidar2world_pose.translation().z() << std::endl; + pose_file.close(); + AINFO << "Saved vehicle pose: " << path; + } + + pcd_save_seq_num_++; +} + // ============================================================================= // Processing // ============================================================================= @@ -285,6 +506,7 @@ bool SpatioTemporalGroundDetector::Detect(const GroundDetectorOptions& options, frame->non_ground_indices.indices.reserve(valid_count); std::vector non_ground_indices; + std::vector ground_indices; if (publish_debug_cloud_) { non_ground_indices.reserve(valid_count); } @@ -297,10 +519,20 @@ bool SpatioTemporalGroundDetector::Detect(const GroundDetectorOptions& options, const uint8_t ground_label = static_cast(LidarPointLabel::GROUND); + // Log statistics for debugging + int ground_count = 0; + int nonground_count = 0; + float max_h_above = -1e6; + float max_h_below = 1e6; + for (size_t i = 0; i < valid_count; ++i) { int idx = idx_ptr[i]; float h = ground_height_signed_[i]; + // Track statistics + if (h > max_h_above) max_h_above = h; + if (h < max_h_below) max_h_below = h; + // Using operator[] is safe here as idx comes from valid indices height_local[idx] = h; height_world[idx] = h; @@ -331,19 +563,41 @@ bool SpatioTemporalGroundDetector::Detect(const GroundDetectorOptions& options, // - otherwise: store absolute point index in the full cloud frame->non_ground_indices.indices.push_back( actual_use_roi ? static_cast(i) : idx); - if (publish_debug_cloud_) { - non_ground_indices.push_back(idx); - } + // Always collect non_ground_indices for PCD saving + non_ground_indices.push_back(idx); + nonground_count++; } else { label_local[idx] = ground_label; label_world[idx] = ground_label; + ground_indices.push_back(idx); + ground_count++; } } + // Log ground detection statistics + // Find max index in ground/non_ground to verify they are within world_cloud bounds + int max_ground_idx = ground_indices.empty() ? -1 : *std::max_element(ground_indices.begin(), ground_indices.end()); + int max_nonground_idx = non_ground_indices.empty() ? -1 : *std::max_element(non_ground_indices.begin(), non_ground_indices.end()); + + AINFO << "Ground detection stats: world_cloud_size=" << frame->world_cloud->size() + << " roi_size=" << (actual_use_roi ? frame->roi_indices.indices.size() : 0) + << " actual_use_roi=" << actual_use_roi + << " processed=" << valid_count + << " ground=" << ground_count << " (" << (100.0*ground_count/valid_count) << "%)" + << " nonground=" << nonground_count << " (" << (100.0*nonground_count/valid_count) << "%)" + << " max_ground_idx=" << max_ground_idx + << " max_nonground_idx=" << max_nonground_idx + << " max_h_above=" << max_h_above << " max_h_below=" << max_h_below; + if (publish_debug_cloud_) { PublishDebugCloud(*frame, non_ground_indices); } + // Save ground and non-ground points as PCD files for debugging + // Pass ROI indices if ROI was used, otherwise nullptr + SaveGroundPcd(*frame, ground_indices, non_ground_indices, + actual_use_roi ? &frame->roi_indices.indices : nullptr); + // 7. Update Global Service (Optional, for Map/Tracker) if (use_ground_service_) { UpdateGroundService(ground_service_content_); diff --git a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.h b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.h index 140bb8b6..f902f458 100644 --- a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.h +++ b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.h @@ -62,6 +62,11 @@ class SpatioTemporalGroundDetector : public BaseGroundDetector { void PublishDebugCloud(const LidarFrame& frame, const std::vector& ground_indices); + void SaveGroundPcd(const LidarFrame& frame, + const std::vector& ground_indices, + const std::vector& non_ground_indices, + const std::vector* processed_indices); + // Internal init logic to share between two Init overrides bool InitInternal(const SpatioTemporalGroundDetectorConfig& config); @@ -93,6 +98,10 @@ class SpatioTemporalGroundDetector : public BaseGroundDetector { debug_writer_ = nullptr; uint32_t debug_seq_num_ = 0; + bool enable_save_ground_pcd_ = false; + std::string ground_pcd_save_dir_; + uint32_t pcd_save_seq_num_ = 0; + SpatioTemporalGroundDetectorConfig config_; }; diff --git a/modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/BUILD b/modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/BUILD new file mode 100644 index 00000000..b1289bcd --- /dev/null +++ b/modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/BUILD @@ -0,0 +1,22 @@ +load("@rules_cc//cc:defs.bzl", "cc_library") +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "polygon_region_filter", + srcs = ["polygon_region_filter.cc"], + hdrs = ["polygon_region_filter.h"], + deps = [ + "//cyber", + "//modules/perception/base:point_cloud", + "//modules/perception/lib/config_manager", + "//modules/perception/lidar/lib/interface:base_object_filter", + "//modules/perception/pipeline:plugin", + "//modules/perception/pipeline/proto/plugin:polygon_region_filter_config_cc_proto", + "@eigen", + ], + alwayslink = True, +) + +cpplint() diff --git a/modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/polygon_region_filter.cc b/modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/polygon_region_filter.cc new file mode 100644 index 00000000..22a8b0fa --- /dev/null +++ b/modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/polygon_region_filter.cc @@ -0,0 +1,267 @@ +/****************************************************************************** + * Copyright 2026 The WheelOS Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ +#include "modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/polygon_region_filter.h" + +#include "cyber/common/file.h" +#include "cyber/common/log.h" +#include "modules/perception/lib/config_manager/config_manager.h" +#include "modules/perception/pipeline/proto/plugin/polygon_region_filter_config.pb.h" + +namespace apollo { +namespace perception { +namespace lidar { + +using PolygonRegionFilterConfig = + apollo::perception::lidar::PolygonRegionFilterConfig; + +bool PolygonRegionObjectFilter::Init(const ObjectFilterInitOptions& options) { + // Legacy init path - load from config manager + auto config_manager = lib::ConfigManager::Instance(); + const lib::ModelConfig* model_config = nullptr; + ACHECK(config_manager->GetModelConfig(Name(), &model_config)); + const std::string work_root = config_manager->work_root(); + std::string root_path; + ACHECK(model_config->get_value("root_path", &root_path)); + const std::string config_dir = + apollo::cyber::common::GetAbsolutePath(work_root, root_path); + std::string config_file = apollo::cyber::common::GetAbsolutePath( + config_dir, "polygon_region_filter.conf"); + PolygonRegionFilterConfig config; + ACHECK(apollo::cyber::common::GetProtoFromFile(config_file, &config)); + return LoadPolygonRegions(config); +} + +bool PolygonRegionObjectFilter::Filter(const ObjectFilterOptions& options, + LidarFrame* frame) { + if (!frame) { + AINFO << "Lidar frame is nullptr."; + return false; + } + + if (exclude_regions_.empty() && include_regions_.empty()) { + // No regions configured, pass through all objects + return true; + } + + const Eigen::Affine3d& pose = frame->lidar2world_pose; + auto& objects = frame->segmented_objects; + + std::vector objects_valid_flag(objects.size(), true); + + for (size_t i = 0; i < objects.size(); ++i) { + const auto& obj = objects[i]; + + // Check if object is in exclude regions + if (!exclude_regions_.empty()) { + bool in_exclude_region = + IsObjectInPolygon(obj, exclude_regions_, pose); + if (in_exclude_region) { + objects_valid_flag[i] = false; + ADEBUG << "Polygon region filter: object " << obj->id + << " filtered out (in exclude region), center " + << obj->center.head<2>().transpose(); + continue; + } + } + + // Check if object is in include regions (if configured) + if (!include_regions_.empty()) { + bool in_include_region = + IsObjectInPolygon(obj, include_regions_, pose); + if (!in_include_region) { + objects_valid_flag[i] = false; + ADEBUG << "Polygon region filter: object " << obj->id + << " filtered out (not in include region), center " + << obj->center.head<2>().transpose(); + } + } + } + + // Remove filtered objects + size_t count = 0; + for (size_t i = 0; i < objects.size(); ++i) { + if (objects_valid_flag[i]) { + if (count != i) { + objects[count] = objects[i]; + } + ++count; + } + } + objects.resize(count); + + AINFO << "Polygon region filter, filtered objects size: from " + << objects_valid_flag.size() << " to " << count; + return true; +} + +bool PolygonRegionObjectFilter::Init(const PluginConfig& plugin_config) { + PolygonRegionFilterConfig config = + plugin_config.polygon_region_filter_config(); + return LoadPolygonRegions(config); +} + +bool PolygonRegionObjectFilter::IsPointInPolygon( + const Eigen::Vector2d& point, const Polygon2D& polygon) const { + if (polygon.points.size() < 3) { + return false; + } + + // Ray casting algorithm + bool inside = false; + size_t n = polygon.points.size(); + + for (size_t i = 0, j = n - 1; i < n; j = i++) { + const Eigen::Vector2d& pi = polygon.points[i]; + const Eigen::Vector2d& pj = polygon.points[j]; + + // Check if point is on vertex + if ((point - pi).norm() < 1e-6 || (point - pj).norm() < 1e-6) { + return true; + } + + // Check if point is on edge + double cross = (pi.y() - pj.y()) * point.x() + + (pj.x() - pi.x()) * point.y() + pi.x() * pj.y() - + pj.x() * pi.y(); + if (std::abs(cross) < 1e-9) { + // Point is on the line containing the edge + double dot = (point - pi).dot(point - pj); + if (dot <= 0) { + return true; // Point is on the edge + } + } + + // Ray casting: count intersections with ray to the right + if ((pi.y() > point.y()) != (pj.y() > point.y())) { + double intersect_x = + (pj.x() - pi.x()) * (point.y() - pi.y()) / (pj.y() - pi.y()) + + pi.x(); + if (point.x() < intersect_x) { + inside = !inside; + } + } + } + + return inside; +} + +bool PolygonRegionObjectFilter::IsObjectInPolygon( + const base::ObjectPtr& object, const std::vector& polygons, + const Eigen::Affine3d& lidar2world) const { + for (const auto& polygon : polygons) { + if (IsObjectPolygonInPolygon(object, polygon, lidar2world)) { + return true; + } + } + return false; +} + +bool PolygonRegionObjectFilter::IsObjectPolygonInPolygon( + const base::ObjectPtr& object, const Polygon2D& polygon, + const Eigen::Affine3d& lidar2world) const { + if (use_center_point_only_) { + return IsObjectCenterInPolygon(object, polygon, lidar2world); + } + + // Check all polygon points of the object + for (const auto& point : object->polygon) { + Eigen::Vector3d local_point(point.x, point.y, point.z); + Eigen::Vector3d world_point = lidar2world * local_point; + + if (use_world_coordinate_) { + Eigen::Vector2d point_2d(world_point.x(), world_point.y()); + if (IsPointInPolygon(point_2d, polygon)) { + return true; + } + } else { + Eigen::Vector2d point_2d(point.x, point.y); + if (IsPointInPolygon(point_2d, polygon)) { + return true; + } + } + } + + // Also check center point as fallback + return IsObjectCenterInPolygon(object, polygon, lidar2world); +} + +bool PolygonRegionObjectFilter::IsObjectCenterInPolygon( + const base::ObjectPtr& object, const Polygon2D& polygon, + const Eigen::Affine3d& lidar2world) const { + Eigen::Vector3d center_point; + if (use_world_coordinate_) { + center_point = lidar2world * object->center; + } else { + center_point = object->center; + } + + Eigen::Vector2d center_2d(center_point.x(), center_point.y()); + return IsPointInPolygon(center_2d, polygon); +} + +bool PolygonRegionObjectFilter::LoadPolygonRegions( + const PolygonRegionFilterConfig& config) { + use_center_point_only_ = config.use_center_point_only(); + use_world_coordinate_ = (config.coordinate_system() == "world"); + + // Load exclude regions + exclude_regions_.clear(); + for (const auto& region_proto : config.exclude_regions()) { + Polygon2D region; + region.name = region_proto.name(); + for (const auto& point : region_proto.points()) { + if (point.has_x() && point.has_y()) { + region.points.push_back(Eigen::Vector2d(point.x(), point.y())); + } + } + if (region.points.size() >= 3) { + exclude_regions_.push_back(region); + AINFO << "Loaded exclude region: " << region.name << " with " + << region.points.size() << " points"; + } else { + AWARN << "Skip exclude region '" << region.name + << "' with less than 3 points"; + } + } + + // Load include regions + include_regions_.clear(); + for (const auto& region_proto : config.include_regions()) { + Polygon2D region; + region.name = region_proto.name(); + for (const auto& point : region_proto.points()) { + if (point.has_x() && point.has_y()) { + region.points.push_back(Eigen::Vector2d(point.x(), point.y())); + } + } + if (region.points.size() >= 3) { + include_regions_.push_back(region); + AINFO << "Loaded include region: " << region.name << " with " + << region.points.size() << " points"; + } else { + AWARN << "Skip include region '" << region.name + << "' with less than 3 points"; + } + } + + return true; +} + +PERCEPTION_REGISTER_OBJECTFILTER(PolygonRegionObjectFilter); + +} // namespace lidar +} // namespace perception +} // namespace apollo diff --git a/modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/polygon_region_filter.h b/modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/polygon_region_filter.h new file mode 100644 index 00000000..baae24b8 --- /dev/null +++ b/modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/polygon_region_filter.h @@ -0,0 +1,95 @@ +/****************************************************************************** + * Copyright 2026 The WheelOS Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ +#pragma once + +#include +#include + +#include "Eigen/Dense" + +#include "modules/common/util/eigen_defs.h" +#include "modules/perception/base/point_cloud.h" +#include "modules/perception/lidar/lib/interface/base_object_filter.h" +#include "modules/perception/pipeline/plugin.h" +#include "modules/perception/pipeline/proto/pipeline_config.pb.h" + +namespace apollo { +namespace perception { +namespace lidar { + +// Polygon region defined by a list of 2D points +struct Polygon2D { + std::string name; + std::vector points; +}; + +class PolygonRegionObjectFilter : public BaseObjectFilter { + public: + using PluginConfig = pipeline::PluginConfig; + + PolygonRegionObjectFilter() { name_ = "PolygonRegionObjectFilter"; } + + explicit PolygonRegionObjectFilter(const PluginConfig& plugin_config) { + name_ = "PolygonRegionObjectFilter"; + Init(plugin_config); + } + + virtual ~PolygonRegionObjectFilter() = default; + + bool Init(const ObjectFilterInitOptions& options = + ObjectFilterInitOptions()) override; + + bool Filter(const ObjectFilterOptions& options, LidarFrame* frame) override; + + bool Init(const PluginConfig& plugin_config) override; + + bool IsEnabled() const override { return enable_; } + + std::string Name() const override { return name_; } + + private: + // Check if a point is inside a polygon using ray casting algorithm + bool IsPointInPolygon(const Eigen::Vector2d& point, + const Polygon2D& polygon) const; + + // Check if an object is inside any of the given polygons + bool IsObjectInPolygon(const base::ObjectPtr& object, + const std::vector& polygons, + const Eigen::Affine3d& lidar2world) const; + + // Check if any point of object polygon is inside the given polygon + bool IsObjectPolygonInPolygon(const base::ObjectPtr& object, + const Polygon2D& polygon, + const Eigen::Affine3d& lidar2world) const; + + // Check if object center is inside the given polygon + bool IsObjectCenterInPolygon(const base::ObjectPtr& object, + const Polygon2D& polygon, + const Eigen::Affine3d& lidar2world) const; + + // Load polygon regions from config + bool LoadPolygonRegions(const PolygonRegionFilterConfig& config); + + private: + std::vector exclude_regions_; + std::vector include_regions_; + bool use_center_point_only_ = false; + bool use_world_coordinate_ = true; +}; + +} // namespace lidar +} // namespace perception +} // namespace apollo diff --git a/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc b/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc index f8603b86..2ebc516b 100644 --- a/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc +++ b/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc @@ -108,6 +108,10 @@ bool HdmapPointCloudRoiFilter::Filter(const ROIFilterOptions& options, return false; } + // [日志1] 输入统计 + size_t input_size = frame->cloud->size(); + AINFO << "[ROI-Filter] Input points: " << input_size; + // Guard: If map is missing (MapManager failed), we pass through everything // or return false depending on safety policy. // Here we assume if hdmap_struct exists but is empty, it means "No Road". @@ -117,6 +121,8 @@ bool HdmapPointCloudRoiFilter::Filter(const ROIFilterOptions& options, frame->roi_indices.indices.resize(frame->cloud->size()); std::iota(frame->roi_indices.indices.begin(), frame->roi_indices.indices.end(), 0); + AINFO << "[ROI-Filter] Result: PASS-THROUGH (no map), " + << frame->roi_indices.indices.size() << " points"; return true; } @@ -125,9 +131,15 @@ bool HdmapPointCloudRoiFilter::Filter(const ROIFilterOptions& options, const auto& road_polys = frame->hdmap_struct->road_polygons; const auto& junc_polys = frame->hdmap_struct->junction_polygons; + // [日志2] 多边形统计 + AINFO << "[ROI-Filter] HDMap polygons: " + << road_polys.size() << " roads + " + << junc_polys.size() << " junctions"; + if (road_polys.empty() && junc_polys.empty()) { AWARN << "No polygons in ROI. Filter out all points."; frame->roi_indices.indices.clear(); + AINFO << "[ROI-Filter] Result: EMPTY (no polygons)"; return true; } @@ -142,16 +154,30 @@ bool HdmapPointCloudRoiFilter::Filter(const ROIFilterOptions& options, TransformPolygonsToLocal(frame->lidar2world_pose, polygons_world_ptr_, polygons_local_); + // [日志3] 坐标转换后 + AINFO << "[ROI-Filter] Transformed " << polygons_local_.size() + << " polygons to local frame"; + // 3. Rasterize Polygons into Bitmap if (!PreparePolygonMask(polygons_local_, &raw_polygons_, &bitmap_)) { AWARN << "Failed to build polygon mask."; return false; } + // [日志4] 位图信息 + AINFO << "[ROI-Filter] Bitmap size: " << bitmap_.map_size().transpose() + << " major_dir: " << (static_cast(bitmap_.dir_major()) == Bitmap2D::DirectionMajor::XMAJOR ? "X" : "Y"); + // 4. Query Bitmap (Filter Points) // This is O(N_points) but extremely fast (array lookup) Bitmap2dFilter(frame->cloud, bitmap_, &(frame->roi_indices)); + // [日志5] 最终结果 + size_t output_size = frame->roi_indices.indices.size(); + double keep_ratio = static_cast(output_size) / input_size * 100.0; + AINFO << "[ROI-Filter] Result: " << output_size << "/" << input_size + << " points kept (" << keep_ratio << "%)"; + // 5. Labeling (for debug/visualization) auto* labels_local = frame->cloud->mutable_points_label(); auto* labels_world = frame->world_cloud->mutable_points_label(); diff --git a/modules/perception/lidar/tools/ground_visualizer/BUILD b/modules/perception/lidar/tools/ground_visualizer/BUILD new file mode 100644 index 00000000..853d3c78 --- /dev/null +++ b/modules/perception/lidar/tools/ground_visualizer/BUILD @@ -0,0 +1,16 @@ +load("@rules_cc//cc:defs.bzl", "cc_binary") + +cc_binary( + name = "ground_analyzer", + srcs = ["ground_analyzer.cc"], + copts = ['-DMODULE_NAME=\\"perception\\"'], + deps = [ + "//cyber", + "//modules/perception/common/i_lib", + "//modules/perception/common/i_lib/pc:i_ground", + "//modules/perception/common/i_lib/pc:i_struct_s", + "//modules/perception/lidar/common:pcl_util", + "@eigen", + ], + visibility = ["//visibility:public"], +) diff --git a/modules/perception/lidar/tools/ground_visualizer/README.md b/modules/perception/lidar/tools/ground_visualizer/README.md new file mode 100644 index 00000000..c0e72f88 --- /dev/null +++ b/modules/perception/lidar/tools/ground_visualizer/README.md @@ -0,0 +1,242 @@ +# Ground Segmentation Visualizer + +## Overview + +Web-based visualization tool to analyze and debug ground segmentation algorithm on PCD files. Uses Three.js for 3D point cloud visualization and calls the real C++ `ground_analyzer` tool via JSON API for accurate ground detection results. + +## Requirements + +- Python 3.6+ with Flask +- Built ground_analyzer binary +- Web browser for 3D visualization + +## Build + +```bash +# Build the ground_analyzer tool +./apollo.sh build_cpu perception/lidar/tools/ground_visualizer/ground_analyzer +``` + +## Usage + +### Starting the Web Server + +```bash +# Navigate to the tool directory +cd modules/perception/lidar/tools/ground_visualizer + +# Start the Flask server +python3 ground_visualizer_web.py +``` + +The server will start on http://localhost:5000 + +### Using the Web Interface + +1. **Open in Browser**: Navigate to http://localhost:5000 +2. **Upload PCD File**: Click "Choose PCD File" and select your point cloud file +3. **Adjust Parameters**: Use sliders to tune ground segmentation parameters in real-time +4. **Run Segmentation**: Click "Run Segmentation" to process +5. **View Results**: 3D visualization shows ground (green) and non-ground (red) points +6. **Debug Info**: Check browser console for detailed detection statistics + +### Command Line Usage + +You can also run ground_analyzer directly: + +```bash +# Basic usage +./bazel-bin/modules/perception/lidar/tools/ground_visualizer/ground_analyzer \ + /apollo/data/confs/zhongtie/debug_ground/ground_1776063769.125587_5.pcd + +# With custom parameters (JSON) +./bazel-bin/modules/perception/lidar/tools/ground_visualizer/ground_analyzer \ + input.pcd --params custom_params.json + +# Save results to PCD files +./bazel-bin/modules/perception/lidar/tools/ground_visualizer/ground_analyzer \ + input.pcd --save_pcd out/result + +# JSON output mode +./bazel-bin/modules/perception/lidar/tools/ground_visualizer/ground_analyzer \ + input.pcd --output_json +``` + +## What It Shows + +### 3D Visualization + +- **Green Points**: Ground points detected by the algorithm +- **Red Points**: Non-ground points (obstacles) +- **Camera View**: Rear-top view of the scene (camera positioned at Y=50, Z=-100 in Apollo coords) +- **Point Cloud Centered**: Automatically centered for better visualization + +### Debug Output + +When running with `--output_json`, the tool provides detailed detection statistics: + +1. **Input Statistics**: Point count, bounding box, coordinate system info +2. **Parameter Values**: All ground segmentation parameters used +3. **ROI Filtering**: Number of points before/after ROI filtering +4. **Grid Distribution**: Number of occupied cells, points per cell statistics +5. **Plane Fitting Results**: + - Cells with successful plane fitting + - Cells with insufficient candidates + - Support point statistics +6. **Ground/Non-Ground Counts**: Final segmentation results + +## Coordinate Systems + +### Apollo Coordinate System +- **X**: Right +- **Y**: Forward +- **Z**: Up + +### Three.js Coordinate System (Visualization) +- **X**: Right (same as Apollo X) +- **Y**: Up (Apollo Z) +- **Z**: Forward (Apollo Y) + +**Transformation**: `positions.push(p[0], p[2], p[1])` converts Apollo (x,y,z) to Three.js (x,y,z) + +## Key Parameters + +### Critical for Uphill Terrain + +**sample_region_z_upper** (default: 0.25m, recommend: 1.0-3.0m) +- Filters points by Z height in the near region (±32m from vehicle) +- Points above this threshold are excluded from ground detection candidates +- **Issue**: If set too low (< 0.5m), valid ground points on uphill terrain are filtered out +- **Solution**: Increase to 1.0m or higher for uphill scenarios + +**sample_region_z_lower** (default: -2.0m) +- Lower Z bound for candidate point filtering +- Should be below expected ground level + +### Plane Fitting Thresholds + +**planefit_dist_thres_near** (default: 0.25m) +- RANSAC inlier threshold for near region +- Points within this distance from fitted plane are considered ground + +**planefit_dist_thres_far** (default: 0.40m) +- RANSAC inlier threshold for far region +- Typically larger than near threshold due to point sparsity + +**planefit_orien_threshold** (default: 30.0°) +- Maximum allowed plane orientation deviation from horizontal +- Used to filter unlikely ground planes + +### ROI Settings + +**roi_region_rad_x**, **roi_region_rad_y**, **roi_region_rad_z** +- Region of interest bounds in meters +- Points outside this region are filtered before processing + +**roi_near_rad** (default: 32.0m) +- Defines the "near region" where different thresholds apply + +### Grid Configuration + +**nr_grids_coarse** (default: 128) +- Number of grid cells along each axis for coarse grid +- Larger values = smaller cells = more precise but slower + +**nr_grids_fine** (default: 512) +- Fine grid resolution for final ground height computation + +## Understanding Ground Detection + +The algorithm uses a grid-based RANSAC approach: + +1. **Grid Division**: Point cloud divided into 2D grid cells (X-Y plane) +2. **Candidate Selection**: Each cell selects points within Z bounds as candidates +3. **Plane Fitting**: RANSAC fits a plane to candidates in each cell +4. **Neighbor Smoothing**: Plane parameters smoothed with neighboring cells +5. **Ground Classification**: Points classified based on distance to fitted plane + +### Common Issues + +**Few/no ground points detected:** +- Check `sample_region_z_upper` - may be filtering valid ground points +- Check `planefit_dist_thres_near` - may be too strict +- Verify ROI settings match your point cloud extent + +**Too many false ground points:** +- Decrease `planefit_dist_thres_near/far` +- Decrease `sample_region_z_upper` +- Check `planefit_orien_threshold` - may need to be lower + +**Poor performance on slopes:** +- Increase `planefit_orien_threshold` to allow steeper slopes +- Increase `planefit_dist_thres` to accommodate slope height variation +- Consider using higher grid resolution for better slope modeling + +## Web Interface Controls + +### Mouse Controls +- **Left Click + Drag**: Rotate view +- **Mouse Wheel**: Zoom in/out +- **Right Click + Drag**: Pan view + +### Parameter Adjustment +- All parameters adjustable via sliders +- Changes applied immediately on next "Run Segmentation" click +- Current parameter values shown in real-time + +### Vehicle Pose +- Optional vehicle position (x, y, z) can be specified +- Used for coordinate transformation if needed +- Defaults to (0, 0, 0) if not provided + +## Troubleshooting + +### Server won't start +```bash +# Install Flask if needed +pip3 install flask +``` + +### "0 ground points" result +1. Check parameter values in browser console debug output +2. Verify `sample_region_z_upper` is not too low +3. Confirm ROI settings include your point cloud +4. Try with default parameters first + +### Visualization issues +- **Black screen**: Point cloud may be outside camera view - check console for point count +- **Wrong colors**: Clear browser cache and reload +- **Slow performance**: Large PCD files (>100K points) may lag - consider downsampling + +## Example Session + +``` +$ cd modules/perception/lidar/tools/ground_visualizer +$ python3 ground_visualizer_web.py + * Running on http://0.0.0.0:5000 + +# In browser, open http://localhost:5000 +# Upload PCD file -> Adjust sample_region_z_upper to 1.5 +# Click "Run Segmentation" +# Check browser console for debug output: + +Ground Segmentation Debug: + Input points: 45000 + After ROI filter: 42356 + Occupied cells: 342/4096 + Successful fits: 287 + Failed fits (insufficient candidates): 55 + Ground points: 28456 + Non-ground points: 13900 +``` + +## File Structure + +``` +ground_visualizer/ +├── ground_analyzer.cc # C++ analysis tool +├── ground_visualizer_web.py # Flask web server +├── visualizer.html # Web interface +├── BUILD # Bazel build config +└── README.md # This file +``` diff --git a/modules/perception/lidar/tools/ground_visualizer/ground_analyzer.cc b/modules/perception/lidar/tools/ground_visualizer/ground_analyzer.cc new file mode 100644 index 00000000..c55a1847 --- /dev/null +++ b/modules/perception/lidar/tools/ground_visualizer/ground_analyzer.cc @@ -0,0 +1,751 @@ +/****************************************************************************** + * Copyright 2026 The WheelOS Team. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "cyber/common/log.h" +#include "modules/perception/common/i_lib/pc/i_ground.h" +#include "modules/perception/lidar/common/pcl_util.h" +#include +#include +#include + +namespace apollo { +namespace perception { +namespace lidar { +namespace tools { + +struct GroundAnalyzerConfig { + uint32_t grid_size = 32; + float ground_thres = 3.0f; + float roi_rad_x = 120.0f; + float roi_rad_y = 120.0f; + float roi_rad_z = 100.0f; + uint32_t nr_smooth_iter = 6; + bool use_roi = true; + bool use_ground_service = true; + float sample_region_z_lower = -3.0f; + float sample_region_z_upper = -1.0f; + float roi_near_rad = 32.0f; + float planefit_orien_threshold = 30.0f; + uint32_t big_grid_size = 512; + uint32_t small_grid_size = 64; + float z_compare_thres = 0.3f; + float smooth_z_thres = 2.0f; + float planefit_dist_thres_near = 1.00f; + float planefit_dist_thres_far = 1.50f; + uint32_t inliers_min_threshold = 3; + float near_range_dist = 10.0f; + float near_range_ground_thres = 3.0f; + float middle_range_dist = 20.0f; + float middle_range_ground_thres = 3.0f; + bool enable_debug_non_ground_cloud = false; + std::string debug_cloud_channel = "/apollo/sensor/perception/nonground/PointCloud2"; + + // Vehicle pose for coordinate transform (world -> vehicle) + float vehicle_x = 0.0f; + float vehicle_y = 0.0f; + float vehicle_z = 0.0f; + + void Print() const { + std::cout << "Ground Analyzer Configuration:" << std::endl; + std::cout << " grid_size: " << grid_size << std::endl; + std::cout << " small_grid_size: " << small_grid_size << std::endl; + std::cout << " big_grid_size: " << big_grid_size << std::endl; + std::cout << " roi_rad_x: " << roi_rad_x << std::endl; + std::cout << " planefit_dist_thres_near: " << planefit_dist_thres_near << std::endl; + std::cout << " planefit_dist_thres_far: " << planefit_dist_thres_far << std::endl; + std::cout << " planefit_orien_threshold: " << planefit_orien_threshold << std::endl; + std::cout << " ground_thres: " << ground_thres << std::endl; + std::cout << " nr_smooth_iter: " << nr_smooth_iter << std::endl; + } +}; + +// Debug information structure +struct DetectionDebugInfo { + unsigned int grid_dim_x = 0; + unsigned int grid_dim_y = 0; + int valid_planes = 0; + int failed_cells = 0; + int total_support = 0; + int ground_count = 0; + int nonground_count = 0; + float min_height = 0; + float max_height = 0; + int cells_with_points = 0; + int empty_cells = 0; + int max_points_in_cell = 0; + + struct PlaneInfo { + unsigned int r, c; + float nx, ny, nz, d; + int support; + float angle_to_x; + }; + std::vector planes; // First few planes for display + + void Print() const { + std::cout << "\n===== Ground Detection Debug Info =====" << std::endl; + std::cout << "Grid dimension: " << grid_dim_x << " x " << grid_dim_y << std::endl; + std::cout << "Grid point distribution:" << std::endl; + std::cout << " Cells with points: " << cells_with_points << " / " << (grid_dim_x * grid_dim_y) << std::endl; + std::cout << " Empty cells: " << empty_cells << std::endl; + std::cout << " Max points in one cell: " << max_points_in_cell << std::endl; + std::cout << "Valid planes: " << valid_planes << " / " << (grid_dim_x * grid_dim_y) << std::endl; + std::cout << "Failed cells: " << failed_cells << std::endl; + std::cout << "Total support points: " << total_support << std::endl; + std::cout << "\nResults: ground=" << ground_count << " (" << (100.0*ground_count/(ground_count+nonground_count)) << "%), " + << "nonground=" << nonground_count << " (" << (100.0*nonground_count/(ground_count+nonground_count)) << "%)" << std::endl; + std::cout << "Height range: [" << min_height << ", " << max_height << "]" << std::endl; + std::cout << "===== End Debug Info =====\n" << std::endl; + } + + void ToJson(std::ostream& out) const { + out << "\"debug\": {"; + out << "\"grid_dim_x\": " << grid_dim_x << ","; + out << "\"grid_dim_y\": " << grid_dim_y << ","; + out << "\"cells_with_points\": " << cells_with_points << ","; + out << "\"empty_cells\": " << empty_cells << ","; + out << "\"max_points_in_cell\": " << max_points_in_cell << ","; + out << "\"valid_planes\": " << valid_planes << ","; + out << "\"failed_cells\": " << failed_cells << ","; + out << "\"total_support\": " << total_support << ","; + out << "\"ground_count\": " << ground_count << ","; + out << "\"nonground_count\": " << nonground_count << ","; + out << "\"min_height\": " << min_height << ","; + out << "\"max_height\": " << max_height << ","; + out << "\"planes\": ["; + for (size_t i = 0; i < planes.size(); ++i) { + const auto& p = planes[i]; + out << "{\"r\":" << p.r << ",\"c\":" << p.c << ","; + out << "\"nx\":" << p.nx << ",\"ny\":" << p.ny << ",\"nz\":" << p.nz << ",\"d\":" << p.d << ","; + out << "\"support\":" << p.support << ",\"angle_to_x\":" << p.angle_to_x << "}"; + if (i < planes.size() - 1) out << ","; + } + out << "]}"; + } +}; + +class GroundAnalyzer { + public: + explicit GroundAnalyzer(const GroundAnalyzerConfig& config) : config_(config) { + // Map from proto field names to PlaneFitGroundDetectorParam field names + // Matches spatio_temporal_ground_detector.cc Init() function exactly + param_.nr_grids_coarse = config.small_grid_size; + param_.nr_grids_fine = config.big_grid_size; + param_.roi_region_rad_x = config.roi_rad_x; + param_.roi_region_rad_y = config.roi_rad_y; + param_.roi_region_rad_z = config.roi_rad_z; + param_.nr_smooth_iter = config.nr_smooth_iter; + param_.sample_region_z_lower = config.sample_region_z_lower; + param_.sample_region_z_upper = config.sample_region_z_upper; + param_.roi_near_rad = config.roi_near_rad; + param_.planefit_orien_threshold = config.planefit_orien_threshold; + param_.planefit_dist_threshold_near = config.planefit_dist_thres_near; + param_.planefit_dist_threshold_far = config.planefit_dist_thres_far; + param_.planefit_filter_threshold = config.z_compare_thres; + param_.candidate_filter_threshold = config.smooth_z_thres; + param_.nr_inliers_min_threshold = config.inliers_min_threshold; + param_.nr_points_max = 500000; + + // Create detector + detector_ = std::make_unique(param_); + detector_->Init(); + } + + bool AnalyzeAndOutputJSON(const std::string& pcd_path, std::ostream& out, + const std::string& save_pcd_path = "") { + // Load PCD file + pcl::PointCloud cloud; + if (pcl::io::loadPCDFile(pcd_path, cloud) == -1) { + out << "{\"error\": \"Failed to load PCD file\"}"; + return false; + } + + // Prepare data - use SAME center logic as system + std::vector points; + std::vector indices; + points.reserve(cloud.size() * 3); + indices.reserve(cloud.size()); + + float cx, cy, cz; + // Use system's center (vehicle pose) if provided, same as system's lidar2world_pose.translation() + if (config_.vehicle_x != 0.0f || config_.vehicle_y != 0.0f || config_.vehicle_z != 0.0f) { + cx = config_.vehicle_x; + cy = config_.vehicle_y; + cz = config_.vehicle_z; + } else { + // Fallback: calculate average + cx = cy = cz = 0; + for (const auto& pt : cloud) { + cx += pt.x; + cy += pt.y; + cz += pt.z; + } + cx /= cloud.size(); + cy /= cloud.size(); + cz /= cloud.size(); + } + + for (size_t i = 0; i < cloud.size(); ++i) { + const auto& pt = cloud[i]; + points.push_back(pt.x - cx); + points.push_back(pt.y - cy); + points.push_back(pt.z - cz); + indices.push_back(static_cast(i)); + } + + // Run ground detection + std::vector heights(cloud.size()); + + bool success = detector_->Detect(points.data(), heights.data(), + cloud.size(), 3); + + if (!success) { + out << "{\"error\": \"Ground detection failed\"}"; + return false; + } + + // Collect debug information + DetectionDebugInfo debug_info = CollectDetectionDebug(cloud, heights); + + // Save PCD files if requested (before JSON output) + if (!save_pcd_path.empty()) { + SaveResultPCD(cloud, heights, save_pcd_path); + } + + // Output JSON + out << "{"; + out << "\"points\": ["; + + for (size_t i = 0; i < cloud.size(); ++i) { + const auto& pt = cloud[i]; + float h = heights[i]; + int label = (h > config_.ground_thres) ? 0 : 1; + + // Output centered coordinates - must match what detector actually processes + out << "[" << (pt.x - cx) << "," << (pt.y - cy) << "," << (pt.z - cz) << "," << label << "]"; + if (i < cloud.size() - 1) out << ","; + } + + out << "],"; + out << "\"config\": {"; + out << "\"small_grid_size\": " << config_.small_grid_size << ","; + out << "\"roi_rad_x\": " << config_.roi_rad_x << ","; + out << "\"planefit_dist_thres_near\": " << config_.planefit_dist_thres_near << ","; + out << "\"planefit_dist_thres_far\": " << config_.planefit_dist_thres_far << ","; + out << "\"ground_thres\": " << config_.ground_thres; + out << "},"; + out << "\"num_points\": " << cloud.size() << ","; + debug_info.ToJson(out); // Add debug info to JSON + out << "}"; + + return true; + } + + bool Analyze(const std::string& pcd_path, const std::string& output_path, + const std::string& save_pcd_path = "") { + // Load PCD file + pcl::PointCloud cloud; + if (pcl::io::loadPCDFile(pcd_path, cloud) == -1) { + std::cerr << "Failed to load PCD file: " << pcd_path << std::endl; + return false; + } + + std::cout << "Loaded " << cloud.size() << " points from " << pcd_path << std::endl; + + // Prepare data for detector + std::vector points; + std::vector indices; + points.reserve(cloud.size() * 3); + indices.reserve(cloud.size()); + + // Calculate bounding box + float min_x = std::numeric_limits::max(); + float max_x = std::numeric_limits::lowest(); + float min_y = std::numeric_limits::max(); + float max_y = std::numeric_limits::lowest(); + float min_z = std::numeric_limits::max(); + float max_z = std::numeric_limits::lowest(); + + for (const auto& pt : cloud) { + min_x = std::min(min_x, pt.x); + max_x = std::max(max_x, pt.x); + min_y = std::min(min_y, pt.y); + max_y = std::max(max_y, pt.y); + min_z = std::min(min_z, pt.z); + max_z = std::max(max_z, pt.z); + } + + std::cout << "Bounding Box: X=[" << min_x << ", " << max_x << "]" + << " Y=[" << min_y << ", " << max_y << "]" + << " Z=[" << min_z << ", " << max_z << "]" << std::endl; + + // Use system's center (lidar2world_pose.translation) if provided + // This must match what the system used for ground detection! + float center_x, center_y, center_z; + if (config_.vehicle_x != 0.0f || config_.vehicle_y != 0.0f || config_.vehicle_z != 0.0f) { + // Use system's center (vehicle pose) + center_x = config_.vehicle_x; + center_y = config_.vehicle_y; + center_z = config_.vehicle_z; + std::cout << "Using system center (from vehicle pose): [" << center_x << ", " << center_y << ", " << center_z << "]" << std::endl; + } else { + // Fallback: calculate average as center + float sum_x = 0, sum_y = 0, sum_z = 0; + for (const auto& pt : cloud) { + sum_x += pt.x; + sum_y += pt.y; + sum_z += pt.z; + } + center_x = sum_x / cloud.size(); + center_y = sum_y / cloud.size(); + center_z = sum_z / cloud.size(); + std::cout << "Using calculated center (average): [" << center_x << ", " << center_y << ", " << center_z << "]" << std::endl; + } + + // Estimate slope + float xy_range = std::sqrt(std::pow(max_x - min_x, 2) + std::pow(max_y - min_y, 2)); + float z_range = max_z - min_z; + float slope_deg = std::atan2(z_range, xy_range) * 180.0f / M_PI; + std::cout << "Estimated slope: " << slope_deg << " degrees" << std::endl; + + // Center points and prepare data (using SAME center as system!) + for (size_t i = 0; i < cloud.size(); ++i) { + const auto& pt = cloud[i]; + points.push_back(pt.x - center_x); + points.push_back(pt.y - center_y); + points.push_back(pt.z - center_z); + indices.push_back(static_cast(i)); + } + + // Run ground detection + std::vector heights(cloud.size()); + bool success = detector_->Detect(points.data(), heights.data(), + cloud.size(), 3); + + if (!success) { + std::cerr << "Ground detection failed!" << std::endl; + return false; + } + + // Collect and print debug information + DetectionDebugInfo debug_info = CollectDetectionDebug(cloud, heights); + debug_info.Print(); + + // Additional analysis for non-JSON mode + float grid_size = config_.roi_rad_x * 2.0f / config_.small_grid_size; + std::cout << "\nGround Fitting Analysis:" << std::endl; + std::cout << " Grid cell size: " << grid_size << "m x " << grid_size << "m" << std::endl; + + std::cout << "\n Height variation in one grid for different slopes:" << std::endl; + for (int slope : {5, 10, 15, 20}) { + float h_var = grid_size * std::tan(slope * M_PI / 180.0f); + std::cout << " " << slope << "° slope: " << h_var << "m"; + if (h_var > config_.planefit_dist_thres_near) { + std::cout << " ❌ EXCEEDS threshold (" << config_.planefit_dist_thres_near << "m)"; + } else { + std::cout << " ✓ OK"; + } + std::cout << std::endl; + } + + // Generate visualization data + GenerateVisualization(cloud, heights, center_x, center_y, center_z, + slope_deg, grid_size, output_path); + + // Save PCD files if requested + if (!save_pcd_path.empty()) { + SaveResultPCD(cloud, heights, save_pcd_path); + } + + return true; + } + + bool SaveResultPCD(const pcl::PointCloud& cloud, + const std::vector& heights, + const std::string& output_prefix) { + // Separate ground and non-ground points using ADAPTIVE threshold + // Input cloud is already CENTERED (pt - center), same as system uses! + // Apollo coordinate: X=right, Y=forward, Z=up + pcl::PointCloud ground_cloud; + pcl::PointCloud nonground_cloud; + pcl::PointCloud labeled_cloud; + + ground_cloud.reserve(cloud.size()); + nonground_cloud.reserve(cloud.size()); + labeled_cloud.reserve(cloud.size()); + + int ground_count = 0; + + for (size_t i = 0; i < cloud.size(); ++i) { + const auto& pt = cloud[i]; + float h = heights[i]; + + // Input is already centered (relative coordinates), use Y directly for forward distance + // Apollo: Y is forward + float threshold = config_.ground_thres; + const float forward_dist = pt.y; + + if (forward_dist > 0.0f && forward_dist < config_.near_range_dist) { + threshold = config_.near_range_ground_thres; + } else if (forward_dist >= config_.near_range_dist && + forward_dist < config_.middle_range_dist) { + threshold = config_.middle_range_ground_thres; + } + + bool is_ground = h <= threshold; + + // Add to labeled cloud with intensity indicating ground/non-ground + PCLPointXYZIT labeled_pt = pt; + labeled_pt.intensity = is_ground ? 1 : 255; + labeled_cloud.push_back(labeled_pt); + + // Add to respective cloud + if (is_ground) { + ground_cloud.push_back(pt); + ground_count++; + } else { + nonground_cloud.push_back(pt); + } + } + + // Save PCD files + pcl::PCDWriter writer; + + std::string ground_path = output_prefix + "_ground.pcd"; + writer.writeBinary(ground_path, ground_cloud); + std::cout << "Saved ground points: " << ground_path + << " (" << ground_cloud.size() << " points)" << std::endl; + + std::string nonground_path = output_prefix + "_nonground.pcd"; + writer.writeBinary(nonground_path, nonground_cloud); + std::cout << "Saved non-ground points: " << nonground_path + << " (" << nonground_cloud.size() << " points)" << std::endl; + + std::string labeled_path = output_prefix + "_labeled.pcd"; + writer.writeBinary(labeled_path, labeled_cloud); + std::cout << "Saved labeled points: " << labeled_path + << " (" << labeled_cloud.size() << " points)" << std::endl; + + return true; + } + + private: + // Collect detailed detection debug information + DetectionDebugInfo CollectDetectionDebug(const pcl::PointCloud& cloud, + const std::vector& heights) { + DetectionDebugInfo info; + + // Get grid information + info.grid_dim_x = detector_->GetGridDimX(); + info.grid_dim_y = detector_->GetGridDimY(); + + // Get grid to check point distribution + // Note: GetGrid() returns const pointer but GetVoxels() is non-const + // We need to cast away const to access voxels + common::VoxelGridXY* grid = const_cast*>(detector_->GetGrid()); + std::vector>& voxels = grid->GetVoxels(); + + for (unsigned int r = 0; r < info.grid_dim_y; ++r) { + for (unsigned int c = 0; c < info.grid_dim_x; ++c) { + unsigned int idx = r * info.grid_dim_x + c; + const common::Voxel& voxel = voxels[idx]; + int nr_points = voxel.NrPoints(); + if (nr_points > 0) { + info.cells_with_points++; + if (nr_points > info.max_points_in_cell) info.max_points_in_cell = nr_points; + } else { + info.empty_cells++; + } + } + } + + // Analyze ground planes + for (unsigned int r = 0; r < info.grid_dim_y; ++r) { + for (unsigned int c = 0; c < info.grid_dim_x; ++c) { + const common::GroundPlaneLiDAR* plane = detector_->GetGroundPlane(r, c); + if (plane && plane->IsValid()) { + info.valid_planes++; + info.total_support += plane->GetNrSupport(); + // Collect first few planes for display + if (info.planes.size() < 10) { + DetectionDebugInfo::PlaneInfo pi; + pi.r = r; + pi.c = c; + pi.nx = plane->params[0]; + pi.ny = plane->params[1]; + pi.nz = plane->params[2]; + pi.d = plane->params[3]; + pi.support = plane->GetNrSupport(); + pi.angle_to_x = plane->GetDegreeNormalToX(); + info.planes.push_back(pi); + } + } else { + info.failed_cells++; + } + } + } + + // Count ground vs non-ground + for (size_t i = 0; i < cloud.size(); ++i) { + if (heights[i] > config_.ground_thres) { + info.nonground_count++; + } else { + info.ground_count++; + } + } + + // Height statistics + info.min_height = heights[0]; + info.max_height = heights[0]; + for (float h : heights) { + if (h < info.min_height) info.min_height = h; + if (h > info.max_height) info.max_height = h; + } + + return info; + } + + void GenerateVisualization(const pcl::PointCloud& cloud, + const std::vector& heights, + float center_x, float center_y, float center_z, + float slope_deg, float grid_size, + const std::string& output_path) { + // Create JSON data for visualization + std::stringstream json; + json << "{\n"; + json << " \"points\": [\n"; + + for (size_t i = 0; i < cloud.size(); ++i) { + const auto& pt = cloud[i]; + float h = heights[i]; + bool is_ground = h <= config_.ground_thres; + + json << " [" << pt.x << "," << pt.y << "," << pt.z << "," + << (is_ground ? "1" : "0") << "]"; + if (i < cloud.size() - 1) json << ","; + json << "\n"; + } + + json << " ],\n"; + json << " \"config\": {\n"; + json << " \"small_grid_size\": " << config_.small_grid_size << ",\n"; + json << " \"roi_rad_x\": " << config_.roi_rad_x << ",\n"; + json << " \"planefit_dist_thres_near\": " << config_.planefit_dist_thres_near << ",\n"; + json << " \"planefit_dist_thres_far\": " << config_.planefit_dist_thres_far << ",\n"; + json << " \"ground_thres\": " << config_.ground_thres << ",\n"; + json << " \"planefit_orien_threshold\": " << config_.planefit_orien_threshold << "\n"; + json << " },\n"; + json << " \"analysis\": {\n"; + json << " \"slope_degrees\": " << slope_deg << ",\n"; + json << " \"grid_size\": " << grid_size << ",\n"; + json << " \"total_points\": " << cloud.size() << ",\n"; + + int ground_count = 0; + for (float h : heights) { + if (h <= config_.ground_thres) ground_count++; + } + json << " \"ground_points\": " << ground_count << ",\n"; + json << " \"nonground_points\": " << (cloud.size() - ground_count) << "\n"; + json << " }\n"; + json << "}\n"; + + // Write JSON file + std::string json_path = output_path + ".json"; + std::ofstream json_file(json_path); + json_file << json.str(); + json_file.close(); + std::cout << "Saved visualization data to: " << json_path << std::endl; + + // HTML generation removed - using web interface instead + } + + + GroundAnalyzerConfig config_; + common::PlaneFitGroundDetectorParam param_; + std::unique_ptr detector_; +}; + +} // namespace tools +} // namespace lidar +} // namespace perception +} // namespace apollo + +int main(int argc, char** argv) { + // Check for help first + for (int i = 1; i < argc; i++) { + std::string arg = argv[i]; + if (arg == "--help" || arg == "-h") { + std::cout << "Usage: " << argv[0] << " [options]" << std::endl; + std::cout << "\nOptions:" << std::endl; + std::cout << " --output Output prefix for JSON and HTML files" << std::endl; + std::cout << " --json Output JSON to stdout (for web API)" << std::endl; + std::cout << " --save_pcd Save ground/nonground/labeled PCD files" << std::endl; + std::cout << " --small_grid_size Number of coarse grids (default: 32)" << std::endl; + std::cout << " --big_grid_size Number of fine grids (default: 256)" << std::endl; + std::cout << " --nr_smooth_iter Number of smooth iterations (default: 5)" << std::endl; + std::cout << " --roi_rad_x ROI radius X (default: 120.0)" << std::endl; + std::cout << " --roi_rad_y ROI radius Y (default: 120.0)" << std::endl; + std::cout << " --roi_rad_z ROI radius Z (default: 100.0)" << std::endl; + std::cout << " --roi_near_rad ROI near radius (default: 32.0)" << std::endl; + std::cout << " --planefit_dist_thres_near Near distance threshold (default: 0.10)" << std::endl; + std::cout << " --planefit_dist_thres_far Far distance threshold (default: 0.20)" << std::endl; + std::cout << " --planefit_orien_threshold Orientation threshold (default: 5.0)" << std::endl; + std::cout << " --z_compare_thres Z compare threshold (default: 0.1)" << std::endl; + std::cout << " --smooth_z_thres Smooth Z threshold (default: 1.0)" << std::endl; + std::cout << " --ground_thres Ground height threshold (default: 3.0)" << std::endl; + std::cout << " --vehicle_x Vehicle position X in world coords (default: 0.0)" << std::endl; + std::cout << " --vehicle_y Vehicle position Y in world coords (default: 0.0)" << std::endl; + std::cout << " --vehicle_z Vehicle position Z in world coords (default: 0.0)" << std::endl; + std::cout << " --vehicle_pose_file Load vehicle pose from file (e.g., 000006_vehicle_*.txt)" << std::endl; + std::cout << "\nExample:" << std::endl; + std::cout << " " << argv[0] << " input.pcd --json --small_grid_size 64 --planefit_dist_thres_near 0.25" << std::endl; + std::cout << " " << argv[0] << " input.pcd --save_pcd result --small_grid_size 64" << std::endl; + return 0; + } + } + + if (argc < 2) { + std::cout << "Usage: " << argv[0] << " [options]" << std::endl; + std::cout << "Use --help for more information" << std::endl; + return 1; + } + + // First argument should be PCD file (skip options) + int pcd_file_idx = -1; + std::string output_prefix = "ground_analysis"; + std::string save_pcd_prefix = ""; + bool json_mode = false; + + // Parse command line options + apollo::perception::lidar::tools::GroundAnalyzerConfig config; + + for (int i = 1; i < argc; i++) { + std::string arg = argv[i]; + if (arg == "--json") { + json_mode = true; + } else if (arg == "--output" && i + 1 < argc) { + output_prefix = argv[++i]; + } else if (arg == "--save_pcd" && i + 1 < argc) { + save_pcd_prefix = argv[++i]; + } else if (arg == "--small_grid_size" && i + 1 < argc) { + config.small_grid_size = std::stoul(argv[++i]); + } else if (arg == "--big_grid_size" && i + 1 < argc) { + config.big_grid_size = std::stoul(argv[++i]); + } else if (arg == "--grid_size" && i + 1 < argc) { + config.grid_size = std::stoul(argv[++i]); + } else if (arg == "--nr_smooth_iter" && i + 1 < argc) { + config.nr_smooth_iter = std::stoul(argv[++i]); + } else if (arg == "--roi_rad_x" && i + 1 < argc) { + config.roi_rad_x = std::stof(argv[++i]); + } else if (arg == "--roi_rad_y" && i + 1 < argc) { + config.roi_rad_y = std::stof(argv[++i]); + } else if (arg == "--roi_rad_z" && i + 1 < argc) { + config.roi_rad_z = std::stof(argv[++i]); + } else if (arg == "--roi_near_rad" && i + 1 < argc) { + config.roi_near_rad = std::stof(argv[++i]); + } else if (arg == "--sample_region_z_lower" && i + 1 < argc) { + config.sample_region_z_lower = std::stof(argv[++i]); + } else if (arg == "--sample_region_z_upper" && i + 1 < argc) { + config.sample_region_z_upper = std::stof(argv[++i]); + } else if (arg == "--planefit_dist_thres_near" && i + 1 < argc) { + config.planefit_dist_thres_near = std::stof(argv[++i]); + } else if (arg == "--planefit_dist_thres_far" && i + 1 < argc) { + config.planefit_dist_thres_far = std::stof(argv[++i]); + } else if (arg == "--planefit_orien_threshold" && i + 1 < argc) { + config.planefit_orien_threshold = std::stof(argv[++i]); + } else if (arg == "--inliers_min_threshold" && i + 1 < argc) { + config.inliers_min_threshold = std::stoul(argv[++i]); + } else if (arg == "--z_compare_thres" && i + 1 < argc) { + config.z_compare_thres = std::stof(argv[++i]); + } else if (arg == "--smooth_z_thres" && i + 1 < argc) { + config.smooth_z_thres = std::stof(argv[++i]); + } else if (arg == "--ground_thres" && i + 1 < argc) { + config.ground_thres = std::stof(argv[++i]); + } else if (arg == "--near_range_dist" && i + 1 < argc) { + config.near_range_dist = std::stof(argv[++i]); + } else if (arg == "--near_range_ground_thres" && i + 1 < argc) { + config.near_range_ground_thres = std::stof(argv[++i]); + } else if (arg == "--middle_range_dist" && i + 1 < argc) { + config.middle_range_dist = std::stof(argv[++i]); + } else if (arg == "--middle_range_ground_thres" && i + 1 < argc) { + config.middle_range_ground_thres = std::stof(argv[++i]); + } else if (arg == "--vehicle_x" && i + 1 < argc) { + config.vehicle_x = std::stof(argv[++i]); + } else if (arg == "--vehicle_y" && i + 1 < argc) { + config.vehicle_y = std::stof(argv[++i]); + } else if (arg == "--vehicle_z" && i + 1 < argc) { + config.vehicle_z = std::stof(argv[++i]); + } else if (arg == "--vehicle_pose_file" && i + 1 < argc) { + // Read vehicle pose from file (generated by system) + std::string pose_file = argv[++i]; + std::ifstream pf(pose_file); + if (pf.is_open()) { + std::string line; + while (std::getline(pf, line)) { + if (line.empty() || line[0] == '#') continue; // Skip comments + std::istringstream iss(line); + if (iss >> config.vehicle_x >> config.vehicle_y >> config.vehicle_z) { + break; // Read first data line + } + } + pf.close(); + std::cout << "Loaded vehicle pose from file: " + << config.vehicle_x << ", " << config.vehicle_y << ", " << config.vehicle_z << std::endl; + } else { + std::cerr << "Warning: Failed to open vehicle pose file: " << pose_file << std::endl; + } + } else if (arg[0] != '-' && pcd_file_idx < 0) { + // This is the PCD file (first non-option argument) + pcd_file_idx = i; + } + } + + if (pcd_file_idx < 1) { + std::cerr << "Error: No PCD file specified" << std::endl; + return 1; + } + + std::string pcd_file = argv[pcd_file_idx]; + + apollo::perception::lidar::tools::GroundAnalyzer analyzer(config); + + if (json_mode) { + // Run in JSON mode (output to stdout for web API) + if (!analyzer.AnalyzeAndOutputJSON(pcd_file, std::cout, save_pcd_prefix)) { + std::cerr << "Analysis failed!" << std::endl; + return 1; + } + } else { + // Run in file output mode + config.Print(); + if (!analyzer.Analyze(pcd_file, output_prefix, save_pcd_prefix)) { + std::cerr << "Analysis failed!" << std::endl; + return 1; + } + std::cout << "\nOpen " << output_prefix << ".html in your browser to view the visualization." << std::endl; + } + + return 0; +} diff --git a/modules/perception/lidar/tools/ground_visualizer/ground_visualizer_web.py b/modules/perception/lidar/tools/ground_visualizer/ground_visualizer_web.py new file mode 100644 index 00000000..f189f269 --- /dev/null +++ b/modules/perception/lidar/tools/ground_visualizer/ground_visualizer_web.py @@ -0,0 +1,237 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- +""" +Interactive Ground Segmentation Visualizer Web Tool +Calls REAL C++ ground segmentation algorithm via ground_analyzer +Copyright 2026 The WheelOS Team. All Rights Reserved. +""" + +import argparse +import os +import sys +import subprocess +import json +from http.server import HTTPServer, SimpleHTTPRequestHandler +import webbrowser +import threading +import time +from urllib.parse import urlparse, parse_qs + +# Path to the C++ ground_analyzer tool +def get_ground_analyzer_path(): + # Try to find the ground_analyzer binary + script_dir = os.path.dirname(os.path.abspath(__file__)) + + # Try common build output paths + possible_paths = [ + os.path.join(script_dir, '../../bazel-bin/modules/perception/lidar/tools/ground_visualizer/ground_analyzer'), + '/apollo/bazel-bin/modules/perception/lidar/tools/ground_visualizer/ground_analyzer', + os.path.join(script_dir, 'ground_analyzer'), + ] + + for path in possible_paths: + if os.path.exists(path): + return path + + # Default to apollo path + return '/apollo/bazel-bin/modules/perception/lidar/tools/ground_visualizer/ground_analyzer' + +def run_ground_segmentation(pcd_path, config): + """Run C++ ground segmentation via ground_analyzer tool""" + + # Get the actual path to the tool + tool_path = get_ground_analyzer_path() + + # Check if tool exists + if not os.path.exists(tool_path): + return {'error': f'Ground analyzer tool not found at {tool_path}. Build it first with: bazel build //modules/perception/lidar/tools/ground_visualizer:ground_analyzer'} + + # Build command + cmd = [ + tool_path, + pcd_path, + '--json', + '--small_grid_size', str(config.get('small_grid_size', 64)), + '--big_grid_size', str(config.get('big_grid_size', 512)), + '--grid_size', str(config.get('grid_size', 32)), + '--nr_smooth_iter', str(config.get('nr_smooth_iter', 6)), + '--roi_rad_x', str(config.get('roi_rad_x', 120.0)), + '--roi_rad_y', str(config.get('roi_rad_y', 120.0)), + '--roi_rad_z', str(config.get('roi_rad_z', 100.0)), + '--roi_near_rad', str(config.get('roi_near_rad', 32.0)), + '--sample_region_z_lower', str(config.get('sample_region_z_lower', -3.0)), + '--sample_region_z_upper', str(config.get('sample_region_z_upper', -1.0)), + '--planefit_dist_thres_near', str(config.get('planefit_dist_thres_near', 1.0)), + '--planefit_dist_thres_far', str(config.get('planefit_dist_thres_far', 1.5)), + '--planefit_orien_threshold', str(config.get('planefit_orien_threshold', 30.0)), + '--inliers_min_threshold', str(config.get('inliers_min_threshold', 3)), + '--z_compare_thres', str(config.get('z_compare_thres', 0.3)), + '--smooth_z_thres', str(config.get('smooth_z_thres', 2.0)), + '--ground_thres', str(config.get('ground_thres', 3.0)), + '--near_range_dist', str(config.get('near_range_dist', 10.0)), + '--near_range_ground_thres', str(config.get('near_range_ground_thres', 3.0)), + '--middle_range_dist', str(config.get('middle_range_dist', 20.0)), + '--middle_range_ground_thres', str(config.get('middle_range_ground_thres', 3.0)), + '--vehicle_x', str(config.get('vehicle_x', 0.0)), + '--vehicle_y', str(config.get('vehicle_y', 0.0)), + '--vehicle_z', str(config.get('vehicle_z', 0.0)), + ] + + # Print command for debugging + print(f"Running: {' '.join(cmd)}") + + try: + # Run C++ tool and capture output + result = subprocess.run(cmd, capture_output=True, text=True, timeout=30) + + if result.returncode != 0: + return {'error': f'Ground analyzer failed: {result.stderr}'} + + # Parse JSON output + return json.loads(result.stdout) + + except subprocess.TimeoutExpired: + return {'error': 'Ground analyzer timeout'} + except json.JSONDecodeError as e: + return {'error': f'Failed to parse output: {str(e)}'} + except Exception as e: + return {'error': str(e)} + +class PCDRequestHandler(SimpleHTTPRequestHandler): + def do_GET(self): + parsed = urlparse(self.path) + + # Serve static files + if parsed.path == '/' or parsed.path == '/visualizer.html': + self.send_response(200) + self.send_header('Content-Type', 'text/html') + self.end_headers() + + html_path = os.path.join(os.path.dirname(__file__), 'visualizer.html') + with open(html_path, 'r') as f: + self.wfile.write(f.read().encode()) + return + + # API endpoint to run ground segmentation + if parsed.path.startswith('/api/segment'): + params = parse_qs(parsed.query) + pcd_path = params.get('path', [''])[0] + + # Get config parameters with error handling + try: + config = { + 'small_grid_size': int(float(params.get('small_grid_size', [64])[0])), + 'big_grid_size': int(float(params.get('big_grid_size', [512])[0])), + 'grid_size': int(float(params.get('grid_size', [32])[0])), + 'nr_smooth_iter': int(float(params.get('nr_smooth_iter', [6])[0])), + 'roi_rad_x': float(params.get('roi_rad_x', [120.0])[0]), + 'roi_rad_y': float(params.get('roi_rad_y', [120.0])[0]), + 'roi_rad_z': float(params.get('roi_rad_z', [100.0])[0]), + 'roi_near_rad': float(params.get('roi_near_rad', [32.0])[0]), + 'sample_region_z_lower': float(params.get('sample_region_z_lower', [-3.0])[0]), + 'sample_region_z_upper': float(params.get('sample_region_z_upper', [-1.0])[0]), + 'planefit_dist_thres_near': float(params.get('planefit_dist_thres_near', [1.0])[0]), + 'planefit_dist_thres_far': float(params.get('planefit_dist_thres_far', [1.5])[0]), + 'planefit_orien_threshold': float(params.get('planefit_orien_threshold', [30.0])[0]), + 'inliers_min_threshold': int(float(params.get('inliers_min_threshold', [3])[0])), + 'z_compare_thres': float(params.get('z_compare_thres', [0.3])[0]), + 'smooth_z_thres': float(params.get('smooth_z_thres', [2.0])[0]), + 'ground_thres': float(params.get('ground_thres', [3.0])[0]), + 'near_range_dist': float(params.get('near_range_dist', [10.0])[0]), + 'near_range_ground_thres': float(params.get('near_range_ground_thres', [3.0])[0]), + 'middle_range_dist': float(params.get('middle_range_dist', [20.0])[0]), + 'middle_range_ground_thres': float(params.get('middle_range_ground_thres', [3.0])[0]), + # Vehicle pose parameters + 'vehicle_x': float(params.get('vehicle_x', [0.0])[0]), + 'vehicle_y': float(params.get('vehicle_y', [0.0])[0]), + 'vehicle_z': float(params.get('vehicle_z', [0.0])[0]), + } + except (ValueError, IndexError) as e: + self.send_response(400) + self.send_header('Content-Type', 'application/json') + self.send_header('Access-Control-Allow-Origin', '*') + self.end_headers() + self.wfile.write(json.dumps({'error': f'Invalid parameter: {str(e)}'}).encode()) + return + + if not pcd_path or not os.path.exists(pcd_path): + self.send_response(404) + self.send_header('Content-Type', 'application/json') + self.end_headers() + self.wfile.write(json.dumps({'error': 'File not found'}).encode()) + return + + try: + # Run ground segmentation using C++ tool + result = run_ground_segmentation(pcd_path, config) + + self.send_response(200) + self.send_header('Content-Type', 'application/json') + self.send_header('Access-Control-Allow-Origin', '*') + self.end_headers() + self.wfile.write(json.dumps(result).encode()) + except Exception as e: + self.send_response(500) + self.send_header('Content-Type', 'application/json') + self.end_headers() + self.wfile.write(json.dumps({'error': str(e)}).encode()) + return + + # Default: serve file from directory + super().do_GET() + + def end_headers(self): + self.send_header('Access-Control-Allow-Origin', '*') + self.send_header('Access-Control-Allow-Methods', 'GET, OPTIONS') + self.send_header('Access-Control-Allow-Headers', 'Content-Type') + super().end_headers() + + def do_OPTIONS(self): + self.send_response(200) + self.end_headers() + +def start_web_server(port=8080): + """Start web server""" + os.chdir(os.path.dirname(os.path.abspath(__file__))) + server = HTTPServer(('localhost', port), PCDRequestHandler) + print(f"Web server started at http://localhost:{port}") + server.serve_forever() + +def main(): + parser = argparse.ArgumentParser(description="Interactive Ground Segmentation Visualizer") + parser.add_argument("pcd_file", nargs='?', help="Path to PCD file to visualize") + parser.add_argument("--port", type=int, default=8080, help="Port for web server") + parser.add_argument("--no-browser", action="store_true", help="Don't open browser automatically") + + args = parser.parse_args() + + # Start web server in background + server_thread = threading.Thread(target=start_web_server, args=(args.port,), daemon=True) + server_thread.start() + + # Open browser + time.sleep(1) + if not args.no_browser: + url = f"http://localhost:{args.port}/visualizer.html" + if args.pcd_file: + url += f"?pcd_path={args.pcd_file}" + print(f"Opening browser at: {url}") + webbrowser.open(url) + + print("\n" + "="*60) + print("Ground Segmentation Visualizer") + print("="*60) + print(f"\nWeb interface available at: http://localhost:{args.port}/visualizer.html") + print("\nThis tool calls the REAL C++ ground segmentation algorithm!") + print(f"Ground analyzer path: {get_ground_analyzer_path()}") + print("\nPress Ctrl+C to stop the server") + print("="*60 + "\n") + + try: + while True: + time.sleep(1) + except KeyboardInterrupt: + print("\nShutting down...") + +if __name__ == "__main__": + sys.exit(main()) diff --git a/modules/perception/lidar/tools/ground_visualizer/visualizer.html b/modules/perception/lidar/tools/ground_visualizer/visualizer.html new file mode 100644 index 00000000..a780f00a --- /dev/null +++ b/modules/perception/lidar/tools/ground_visualizer/visualizer.html @@ -0,0 +1,889 @@ + + + + + Ground Segmentation Visualizer + + + + + +
+
+
+
Loading...
+
+
+
+

Ground Segmentation Visualizer

+ +
+ + + + +
+ +
+ +
+
+ + +
+
+ + +
+
+ + +
+
+
+ + +
+
+ +
+ ℹ️ This tool runs REAL ground segmentation algorithm! +

+ Adjust parameters and click "Load & Run Segmentation" to see how different settings affect the results. +

+
+ +
+
+
+ Ground (intensity=1) +
+
+
+ Non-ground (intensity=255) +
+
+ +

Algorithm Parameters

+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+ + +
+ +
+

Ground Fitting Analysis

+
+

Load a PCD file to see analysis...

+
+
+ + +
+
+ + + + diff --git a/modules/perception/onboard/component/lidar_detection_component.cc b/modules/perception/onboard/component/lidar_detection_component.cc index 83a2c270..4cebb054 100644 --- a/modules/perception/onboard/component/lidar_detection_component.cc +++ b/modules/perception/onboard/component/lidar_detection_component.cc @@ -16,6 +16,7 @@ #include "modules/perception/onboard/component/lidar_detection_component.h" #include "cyber/time/clock.h" +#include "modules/perception/onboard/msg_serializer/msg_serializer.h" #include "modules/common/util/string_util.h" #include "modules/perception/common/sensor_manager/sensor_manager.h" #include "modules/perception/lidar/common/lidar_error_code.h" @@ -49,6 +50,7 @@ bool LidarDetectionComponent::Init() { static_cast(comp_config.lidar_query_tf_offset()); enable_hdmap_ = comp_config.enable_hdmap(); writer_ = node_->CreateWriter(output_channel_name_); + debug_writer_ = node_->CreateWriter("/apollo/perception/obstacles"); const auto& lidar_detection_root_dir = comp_config.lidar_detection_conf_dir(); const auto& lidar_detection_conf_file = @@ -84,6 +86,18 @@ bool LidarDetectionComponent::Proc( if (status) { writer_->Write(out_message); AINFO << "Send lidar detect output message."; + + // 额外输出protobuf到 /apollo/perception/obstacles 用于调试 + auto debug_msg = std::make_shared(); + MsgSerializer::SerializeMsg( + out_message->timestamp_, + out_message->lidar_timestamp_, + out_message->seq_num_, + out_message->lidar_frame_->segmented_objects, + out_message->error_code_, + debug_msg.get()); + debug_writer_->Write(debug_msg); + AINFO << "Send detection debug output to /apollo/perception/obstacles"; } return status; } @@ -173,10 +187,12 @@ bool LidarDetectionComponent::InternalProc( Eigen::Affine3d pose_vehicle = Eigen::Affine3d::Identity(); const double lidar_query_tf_timestamp = timestamp - lidar_query_tf_offset_ * 0.001; + // const double lidar_query_tf_timestamp = cyber::Time::Now().ToSecond() - 0.1; if (!lidar2world_trans_.GetSensor2worldTrans(lidar_query_tf_timestamp, &pose, &pose_vehicle)) { out_message->error_code_ = apollo::common::ErrorCode::PERCEPTION_ERROR_TF; - AERROR << "Failed to get pose at time: " << lidar_query_tf_timestamp; + AERROR << std::fixed << std::setprecision(9) + << "Failed to get pose at time: " << lidar_query_tf_timestamp; return false; } diff --git a/modules/perception/onboard/component/lidar_detection_component.h b/modules/perception/onboard/component/lidar_detection_component.h index 58ef6ba5..cf484990 100644 --- a/modules/perception/onboard/component/lidar_detection_component.h +++ b/modules/perception/onboard/component/lidar_detection_component.h @@ -27,6 +27,7 @@ #include "modules/perception/onboard/transform_wrapper/transform_wrapper.h" #include "modules/common_msgs/sensor_msgs/pointcloud.pb.h" +#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h" #include "modules/perception/onboard/proto/lidar_component_config.pb.h" namespace apollo { @@ -71,6 +72,7 @@ class LidarDetectionComponent : public cyber::Component { pipeline::PipelineConfig lidar_detection_config_; std::shared_ptr> writer_; + std::shared_ptr> debug_writer_; }; CYBER_REGISTER_COMPONENT(LidarDetectionComponent); diff --git a/modules/perception/onboard/component/lidar_tracking_component.cc b/modules/perception/onboard/component/lidar_tracking_component.cc index 54c05973..b3a56d22 100644 --- a/modules/perception/onboard/component/lidar_tracking_component.cc +++ b/modules/perception/onboard/component/lidar_tracking_component.cc @@ -16,6 +16,7 @@ #include "modules/perception/onboard/component/lidar_tracking_component.h" #include "cyber/time/clock.h" +#include "modules/perception/onboard/msg_serializer/msg_serializer.h" #include "modules/common/util/perf_util.h" #include "modules/perception/base/object_pool_types.h" #include "modules/perception/common/sensor_manager/sensor_manager.h" @@ -39,6 +40,7 @@ bool LidarTrackingComponent::Init() { output_channel_name_ = comp_config.output_channel_name(); main_sensor_name_ = comp_config.main_sensor_name(); writer_ = node_->CreateWriter(output_channel_name_); + debug_writer_ = node_->CreateWriter("/apollo/perception/obstacles"); // read pipeline config std::string lidar_tracking_conf_dir = comp_config.lidar_tracking_conf_dir(); @@ -75,6 +77,18 @@ bool LidarTrackingComponent::Proc( if (InternalProc(message, out_message)) { writer_->Write(out_message); AINFO << "Send lidar recognition output message."; + + // 额外输出protobuf到 /apollo/perception/obstacles 用于调试 + auto debug_msg = std::make_shared(); + MsgSerializer::SerializeMsg( + out_message->timestamp_, + out_message->lidar_timestamp_, + out_message->seq_num_, + out_message->frame_->objects, + out_message->error_code_, + debug_msg.get()); + debug_writer_->Write(debug_msg); + AINFO << "Send tracking debug output to /apollo/perception/obstacles"; return true; } return false; diff --git a/modules/perception/onboard/component/lidar_tracking_component.h b/modules/perception/onboard/component/lidar_tracking_component.h index 0ecb4ffa..3fa05d70 100644 --- a/modules/perception/onboard/component/lidar_tracking_component.h +++ b/modules/perception/onboard/component/lidar_tracking_component.h @@ -25,6 +25,7 @@ #include "modules/perception/onboard/inner_component_messages/lidar_inner_component_messages.h" #include "modules/perception/onboard/proto/lidar_component_config.pb.h" #include "modules/perception/pipeline/pipeline.h" +#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h" namespace apollo { namespace perception { @@ -54,6 +55,7 @@ class LidarTrackingComponent : public cyber::Component { std::string main_sensor_name_; std::string output_channel_name_; std::shared_ptr> writer_; + std::shared_ptr> debug_writer_; }; CYBER_REGISTER_COMPONENT(LidarTrackingComponent); diff --git a/modules/perception/pipeline/BUILD b/modules/perception/pipeline/BUILD index 5c716009..ed6565de 100644 --- a/modules/perception/pipeline/BUILD +++ b/modules/perception/pipeline/BUILD @@ -54,6 +54,7 @@ cc_library( "//modules/perception/camera/lib/obstacle/preprocessor/get_image_data", "//modules/perception/camera/lib/obstacle/preprocessor/resize_and_normalize", "//modules/perception/lidar/lib/classifier/fused_classifier:ccrf_type_fusion", + "//modules/perception/lidar/lib/object_filter_bank/polygon_region_filter", "//modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter", "//modules/perception/lidar/lib/pointcloud_detection_postprocessor/pointcloud_get_objects", "//modules/perception/lidar/lib/pointcloud_detection_preprocessor/pointcloud_down_sample", diff --git a/modules/perception/pipeline/plugin_factory.cc b/modules/perception/pipeline/plugin_factory.cc index adbf95d0..081dceff 100644 --- a/modules/perception/pipeline/plugin_factory.cc +++ b/modules/perception/pipeline/plugin_factory.cc @@ -23,6 +23,7 @@ #include "modules/perception/camera/lib/obstacle/preprocessor/resize_and_normalize/resize_and_normalize.h" #include "modules/perception/fusion/lib/gatekeeper/pbf_gatekeeper/pbf_gatekeeper.h" #include "modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.h" +#include "modules/perception/lidar/lib/object_filter_bank/polygon_region_filter/polygon_region_filter.h" #include "modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.h" #include "modules/perception/lidar/lib/pointcloud_detection_postprocessor/pointcloud_get_objects/pointcloud_get_objects.h" #include "modules/perception/lidar/lib/pointcloud_detection_preprocessor/pointcloud_down_sample/pointcloud_down_sample.h" @@ -45,6 +46,11 @@ void PluginFactory::Init() { return new lidar::HdmapBoundaryObjectFilter( plugin_config); }); + plugin_factory_.Register(PluginType::POLYGON_REGION_FILTER, + [](const PluginConfig& plugin_config) -> Plugin* { + return new lidar::PolygonRegionObjectFilter( + plugin_config); + }); plugin_factory_.Register( PluginType::POINTCLOUD_GET_OBJECTS, [](const PluginConfig& plugin_config) -> Plugin* { diff --git a/modules/perception/pipeline/proto/BUILD b/modules/perception/pipeline/proto/BUILD index c3bb7d0e..19659a51 100644 --- a/modules/perception/pipeline/proto/BUILD +++ b/modules/perception/pipeline/proto/BUILD @@ -45,6 +45,7 @@ proto_library( "//modules/perception/pipeline/proto/plugin:pbf_gatekeeper_config_proto", "//modules/perception/pipeline/proto/plugin:pointcloud_downsample_config_proto", "//modules/perception/pipeline/proto/plugin:pointcloud_get_objects_config_proto", + "//modules/perception/pipeline/proto/plugin:polygon_region_filter_config_proto", "//modules/perception/pipeline/proto/plugin:recover_bbox_config_proto", "//modules/perception/pipeline/proto/plugin:resize_and_normalize_config_proto", "//modules/perception/pipeline/proto/plugin:roi_boundary_filter_config_proto", diff --git a/modules/perception/pipeline/proto/pipeline_config.proto b/modules/perception/pipeline/proto/pipeline_config.proto index 6dcdb6e4..cdf5d763 100644 --- a/modules/perception/pipeline/proto/pipeline_config.proto +++ b/modules/perception/pipeline/proto/pipeline_config.proto @@ -13,6 +13,7 @@ import "modules/perception/pipeline/proto/plugin/multi_lidar_fusion_config.proto import "modules/perception/pipeline/proto/plugin/pbf_gatekeeper_config.proto"; import "modules/perception/pipeline/proto/plugin/pointcloud_downsample_config.proto"; import "modules/perception/pipeline/proto/plugin/pointcloud_get_objects_config.proto"; +import "modules/perception/pipeline/proto/plugin/polygon_region_filter_config.proto"; import "modules/perception/pipeline/proto/plugin/recover_bbox_config.proto"; import "modules/perception/pipeline/proto/plugin/resize_and_normalize_config.proto"; import "modules/perception/pipeline/proto/plugin/roi_boundary_filter_config.proto"; @@ -82,6 +83,7 @@ enum PluginType { PBF_GATEKEEPER = 13; POINTCLOUD_DOWNSAMPLE = 14; + POLYGON_REGION_FILTER = 15; } message PluginConfig { @@ -104,6 +106,7 @@ message PluginConfig { lidar.MlfTrackerConfig mlf_tracker_config = 19; lidar.CcrfTypeFusionConfig ccrf_type_fusion_config = 20; fusion.PbfGatekeeperConfig pbf_gatekeeper_config = 21; + lidar.PolygonRegionFilterConfig polygon_region_filter_config = 22; } } diff --git a/modules/perception/pipeline/proto/plugin/BUILD b/modules/perception/pipeline/proto/plugin/BUILD index cd0ff2d3..5f16c4d4 100644 --- a/modules/perception/pipeline/proto/plugin/BUILD +++ b/modules/perception/pipeline/proto/plugin/BUILD @@ -225,3 +225,20 @@ py_proto_library( name = "pointcloud_get_objects_config_py_pb2", deps = [":pointcloud_get_objects_config_proto"], ) + +cc_proto_library( + name = "polygon_region_filter_config_cc_proto", + deps = [ + ":polygon_region_filter_config_proto", + ], +) + +proto_library( + name = "polygon_region_filter_config_proto", + srcs = ["polygon_region_filter_config.proto"], +) + +py_proto_library( + name = "polygon_region_filter_config_py_pb2", + deps = [":polygon_region_filter_config_proto"], +) diff --git a/modules/perception/pipeline/proto/plugin/polygon_region_filter_config.proto b/modules/perception/pipeline/proto/plugin/polygon_region_filter_config.proto new file mode 100644 index 00000000..717619cc --- /dev/null +++ b/modules/perception/pipeline/proto/plugin/polygon_region_filter_config.proto @@ -0,0 +1,40 @@ +/****************************************************************************** + * Copyright 2026 The WheelOS Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ +syntax = "proto2"; + +package apollo.perception.lidar; + +message Point2D { + optional double x = 1; + optional double y = 2; +} + +message PolygonRegion { + optional string name = 1; + repeated Point2D points = 2; +} + +message PolygonRegionFilterConfig { + // Regions to exclude objects (objects inside these regions will be filtered out) + repeated PolygonRegion exclude_regions = 1; + // Regions to include objects (only objects inside these regions will be kept) + // If empty, all objects not in exclude_regions are kept + repeated PolygonRegion include_regions = 2; + // If true, only check object center point; otherwise check all polygon points + optional bool use_center_point_only = 3 [default = false]; + // Coordinate system for polygon points: "local" (lidar) or "world" + optional string coordinate_system = 4 [default = "world"]; +} diff --git a/modules/perception/pipeline/proto/stage/spatio_temporal_ground_detector_config.proto b/modules/perception/pipeline/proto/stage/spatio_temporal_ground_detector_config.proto index db9cad94..c5cccb70 100644 --- a/modules/perception/pipeline/proto/stage/spatio_temporal_ground_detector_config.proto +++ b/modules/perception/pipeline/proto/stage/spatio_temporal_ground_detector_config.proto @@ -41,4 +41,9 @@ message SpatioTemporalGroundDetectorConfig { optional bool enable_debug_non_ground_cloud = 24 [default = false]; optional string debug_cloud_channel = 25 [default = "/apollo/sensor/perception/nonground/PointCloud2"]; + + // Debug PCD save settings for ground segmentation analysis + optional bool enable_save_ground_pcd = 26 [default = false]; + optional string ground_pcd_save_dir = 27 + [default = "/apollo/data/ground_segmentation_debug/"]; } diff --git a/modules/perception/production/conf/perception/lidar/lidar_segmentation_conf.pb.txt b/modules/perception/production/conf/perception/lidar/lidar_segmentation_conf.pb.txt index 68ffd7e6..1048a9d7 100644 --- a/modules/perception/production/conf/perception/lidar/lidar_segmentation_conf.pb.txt +++ b/modules/perception/production/conf/perception/lidar/lidar_segmentation_conf.pb.txt @@ -1,4 +1,4 @@ -sensor_name: "velodyne128" +sensor_name: "base_link" detector_name: "LidarObstacleDetection" enable_hdmap: true lidar_query_tf_offset: 0