Skip to content

Commit

Permalink
fix(behavior_velocity): avoid zero division in pcl (tier4#1183)
Browse files Browse the repository at this point in the history
* fix(behavior_velocity): avoid zero division in pcl

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>

* remove unnecessary comments

Signed-off-by: Tomohito Ando <tomohito.ando@tier4.jp>
  • Loading branch information
TomohitoAndo authored and boyali committed Oct 3, 2022
1 parent fdad56d commit 390ed03
Showing 1 changed file with 6 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,6 @@ pcl::PointCloud<pcl::PointXYZ> applyVoxelGridFilter(
p.z = 0.0;
}

// use boost::makeshared instead of std beacause filter.setInputCloud requires boost shared ptr
pcl::VoxelGrid<pcl::PointXYZ> filter;
filter.setInputCloud(pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(no_height_points));
filter.setLeafSize(0.05f, 0.05f, 100000.0f);
Expand Down Expand Up @@ -197,6 +196,12 @@ std::vector<DynamicObstacle> DynamicObstacleCreatorForPoints::createDynamicObsta
void DynamicObstacleCreatorForPoints::onCompareMapFilteredPointCloud(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
{
if (msg->data.empty()) {
std::lock_guard<std::mutex> lock(mutex_);
dynamic_obstacle_data_.compare_map_filtered_pointcloud.clear();
return;
}

geometry_msgs::msg::TransformStamped transform;
try {
transform = tf_buffer_.lookupTransform(
Expand Down

0 comments on commit 390ed03

Please sign in to comment.