Skip to content

Commit

Permalink
fix: roi_pointcloud_fusion with new template
Browse files Browse the repository at this point in the history
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
  • Loading branch information
badai-nguyen committed Nov 21, 2023
1 parent f5140e0 commit da10c3e
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 3 deletions.
4 changes: 2 additions & 2 deletions perception/image_projection_based_fusion/src/fusion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -420,7 +420,7 @@ void FusionNode<Msg, Obj, Msg2D>::publish(const Msg & output_msg)
template class FusionNode<DetectedObjects, DetectedObject, DetectedObjectsWithFeature>;
template class FusionNode<
DetectedObjectsWithFeature, DetectedObjectWithFeature, DetectedObjectsWithFeature>;
template class FusionNode<
sensor_msgs::msg::PointCloud2, DetectedObjects, DetectedObjectsWithFeature>;
template class FusionNode<PointCloud2, DetectedObjects, DetectedObjectsWithFeature>;
template class FusionNode<PointCloud2, DetectedObjectWithFeature, DetectedObjectsWithFeature>;
template class FusionNode<PointCloud2, PointCloud2, Image>;
} // namespace image_projection_based_fusion
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,8 @@
namespace image_projection_based_fusion
{
RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & options)
: FusionNode<PointCloud2, DetectedObjectWithFeature>("roi_pointcloud_fusion", options)
: FusionNode<PointCloud2, DetectedObjectWithFeature, DetectedObjectsWithFeature>(
"roi_pointcloud_fusion", options)
{
fuse_unknown_only_ = declare_parameter<bool>("fuse_unknown_only");
min_cluster_size_ = declare_parameter<int>("min_cluster_size");
Expand Down

0 comments on commit da10c3e

Please sign in to comment.