Skip to content

Commit

Permalink
Refactor
Browse files Browse the repository at this point in the history
  • Loading branch information
HiroIshida committed Apr 6, 2022
1 parent 8f92448 commit cbab6a5
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,9 @@ class PointCloudCreator
const ObjectInfo & obj_info, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator, pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud) const = 0;

virtual void create_multi(
virtual std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> create_pointclouds(
const std::vector<ObjectInfo> & obj_infos, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator, std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> & pointclouds,
std::mt19937 & random_generator,
pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const = 0;
};

Expand All @@ -77,9 +77,9 @@ class ObjectCentricPointCloudCreator : public PointCloudCreator
const ObjectInfo & obj_info, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator, pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud) const override;

void create_multi(
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> create_pointclouds(
const std::vector<ObjectInfo> & obj_infos, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator, std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> & pointclouds,
std::mt19937 & random_generator,
pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const override;

bool enable_ray_tracing_;
Expand All @@ -91,9 +91,9 @@ class VehicleCentricPointCloudCreator : public PointCloudCreator
const ObjectInfo & obj_info, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator, pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud) const override;

void create_multi(
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> create_pointclouds(
const std::vector<ObjectInfo> & obj_infos, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator, std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> & pointclouds,
std::mt19937 & random_generator,
pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const override;
};

Expand Down
5 changes: 2 additions & 3 deletions simulator/dummy_perception_publisher/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,10 +142,9 @@ void DummyPerceptionPublisherNode::timerCallback()
obj_infos.push_back(obj_info);
}

std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> v_pointcloud;
pcl::PointCloud<pcl::PointXYZ>::Ptr merged_pointcloud_ptr(new pcl::PointCloud<pcl::PointXYZ>);
pointcloud_creator_->create_multi(
obj_infos, tf_base_link2map, random_generator_, v_pointcloud, merged_pointcloud_ptr);
const auto v_pointcloud = pointcloud_creator_->create_pointclouds(
obj_infos, tf_base_link2map, random_generator_, merged_pointcloud_ptr);
pcl::toROSMsg(*merged_pointcloud_ptr, output_pointcloud_msg);

std::vector<size_t> delete_idxs;
Expand Down
18 changes: 10 additions & 8 deletions simulator/dummy_perception_publisher/src/pointcloud_creator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,10 +132,9 @@ void ObjectCentricPointCloudCreator::create(
}
}

void ObjectCentricPointCloudCreator::create_multi(
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> ObjectCentricPointCloudCreator::create_pointclouds(
const std::vector<ObjectInfo> & obj_infos, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator, std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> & pointclouds,
pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const
std::mt19937 & random_generator, pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const
{
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> pointclouds_tmp;
pcl::PointCloud<pcl::PointXYZ>::Ptr merged_pointcloud_tmp(new pcl::PointCloud<pcl::PointXYZ>);
Expand All @@ -153,9 +152,8 @@ void ObjectCentricPointCloudCreator::create_multi(
}

if (!enable_ray_tracing_) {
pointclouds = pointclouds_tmp;
merged_pointcloud = merged_pointcloud_tmp;
return;
return pointclouds_tmp;
}

pcl::PointCloud<pcl::PointXYZ>::Ptr ray_traced_merged_pointcloud_ptr(
Expand All @@ -164,6 +162,7 @@ void ObjectCentricPointCloudCreator::create_multi(
ray_tracing_filter.setInputCloud(merged_pointcloud_tmp);
ray_tracing_filter.setLeafSize(0.25, 0.25, 0.25);
ray_tracing_filter.initializeVoxelGrid();
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> pointclouds;
for (size_t i = 0; i < pointclouds_tmp.size(); ++i) {
pcl::PointCloud<pcl::PointXYZ>::Ptr ray_traced_pointcloud_ptr(
new pcl::PointCloud<pcl::PointXYZ>);
Expand All @@ -185,6 +184,7 @@ void ObjectCentricPointCloudCreator::create_multi(
pointclouds.push_back(ray_traced_pointcloud_ptr);
}
merged_pointcloud = ray_traced_merged_pointcloud_ptr;
return pointclouds;
}

void VehicleCentricPointCloudCreator::create(
Expand Down Expand Up @@ -213,11 +213,12 @@ void VehicleCentricPointCloudCreator::create(
}
}

void VehicleCentricPointCloudCreator::create_multi(
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr>
VehicleCentricPointCloudCreator::create_pointclouds(
const std::vector<ObjectInfo> & obj_infos, const tf2::Transform & tf_base_link2map,
std::mt19937 & random_generator, std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> & pointclouds,
pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const
std::mt19937 & random_generator, pcl::PointCloud<pcl::PointXYZ>::Ptr & merged_pointcloud) const
{
std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> pointclouds;
for (const auto & obj_info : obj_infos) {
pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud_shared_ptr(new pcl::PointCloud<pcl::PointXYZ>);
this->create(obj_info, tf_base_link2map, random_generator, pointcloud_shared_ptr);
Expand All @@ -229,4 +230,5 @@ void VehicleCentricPointCloudCreator::create_multi(
merged_pointcloud->push_back(pointclouds.at(i)->at(j));
}
}
return pointclouds;
}

0 comments on commit cbab6a5

Please sign in to comment.