Skip to content

Commit

Permalink
Always initialize clearing endpoints in voxel layer (#2705)
Browse files Browse the repository at this point in the history
  • Loading branch information
m2-farzan authored Nov 25, 2021
1 parent 9cc4192 commit b8d3611
Showing 1 changed file with 5 additions and 7 deletions.
12 changes: 5 additions & 7 deletions nav2_costmap_2d/plugins/voxel_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -333,13 +333,11 @@ void VoxelLayer::raytraceFreespace(
publish_clearing_points = (node->count_subscribers("clearing_endpoints") > 0);
}

if (publish_clearing_points) {
clearing_endpoints_->data.clear();
clearing_endpoints_->width = clearing_observation.cloud_->width;
clearing_endpoints_->height = clearing_observation.cloud_->height;
clearing_endpoints_->is_dense = true;
clearing_endpoints_->is_bigendian = false;
}
clearing_endpoints_->data.clear();
clearing_endpoints_->width = clearing_observation.cloud_->width;
clearing_endpoints_->height = clearing_observation.cloud_->height;
clearing_endpoints_->is_dense = true;
clearing_endpoints_->is_bigendian = false;

sensor_msgs::PointCloud2Modifier modifier(*clearing_endpoints_);
modifier.setPointCloud2Fields(
Expand Down

0 comments on commit b8d3611

Please sign in to comment.