AutoLidarPerception/kitti_ros

Not correct to use 3D bounding box's vertex min/max value for 2D bounding box

Durant35 opened this issue · 2 comments

  • Change to use 4 ground points for Bird's Eye View bounding box
  • Solve the Bounding Box inner point cloud clustering

刘老师觉得 BB/OBB 并不会是影响 Tracking 结果的重要因素

pcl::CropBox + pcl::ConditionalRemoval 似乎行不通

// TODO pcl::CropBox seems working not well
pcl::CropBox<PointI> OBBFilter(true);
OBBFilter.setTranslation(center);
OBBFilter.setRotation(Eigen::Vector3f(0., 0., yaw));
OBBFilter.setMin(Eigen::Vector4f(center(0)-size(0)/2, center(1)-size(1)/2, center(2), 1.0));
OBBFilter.setMax(Eigen::Vector4f(center(0)+size(0)/2, center(1)+size(1)/2, center(2)+size(2), 1.0));
OBBFilter.setInputCloud(cloud);
OBBFilter.setNegative(false);

PointICloudPtr cluster(new PointICloud);
OBBFilter.filter(*cluster);

pcl::transformPointCloud(*cloud, *cloud_transformed, transform);

pcl::ConditionAnd<PointI>::Ptr range_cond(new pcl::ConditionAnd<PointI>());
range_cond->addComparison(
        pcl::FieldComparison<PointI>::ConstPtr(
                new pcl::FieldComparison<PointI>("z", pcl::ComparisonOps::GT, center(2))
        )
);
range_cond->addComparison(
        pcl::FieldComparison<PointI>::ConstPtr(
                new pcl::FieldComparison<PointI>("z", pcl::ComparisonOps::LT, center(2)+size(2))
        )
);
range_cond->addComparison(
        pcl::FieldComparison<PointI>::ConstPtr(
                new pcl::FieldComparison<PointI>("x", pcl::ComparisonOps::GT, center(0)-size(0)/2)
        )
);
range_cond->addComparison(
        pcl::FieldComparison<PointI>::ConstPtr(
                new pcl::FieldComparison<PointI>("x", pcl::ComparisonOps::LT, center(0)+size(0)/2)
        )
);
range_cond->addComparison(
        pcl::FieldComparison<PointI>::ConstPtr(
                new pcl::FieldComparison<PointI>("y", pcl::ComparisonOps::GT, center(1)+size(1)/2)
        )
);
range_cond->addComparison(
        pcl::FieldComparison<PointI>::ConstPtr(
                new pcl::FieldComparison<PointI>("y", pcl::ComparisonOps::LT, center(1)-size(1)/2)
        )
);
// build the filter
pcl::ConditionalRemoval<PointI> condrem;
condrem.setCondition(range_cond);
condrem.setInputCloud(cloud_transformed);
//condrem.setKeepOrganized(true);
// apply filter
condrem.filter(*cluster);