Skip to content

Commit

Permalink
chore: rename Det2dManager to Det2dStatus
Browse files Browse the repository at this point in the history
Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin committed Dec 27, 2024
1 parent d8646c2 commit 3c73ba9
Show file tree
Hide file tree
Showing 12 changed files with 17 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ using autoware::image_projection_based_fusion::CameraProjection;
using autoware_perception_msgs::msg::ObjectClassification;

template <class Msg2D>
struct Det2dManager
struct Det2dStatus
{
// camera index
std::size_t id = 0;
Expand Down Expand Up @@ -116,7 +116,7 @@ class FusionNode : public rclcpp::Node
}
return true;
}
void setDet2dFused(Det2dManager<Msg2D> & det2d)
void setDet2dFused(Det2dStatus<Msg2D> & det2d)
{
std::lock_guard<std::mutex> lock_det2d_flags(mutex_det2d_flags_);
det2d.is_fused = true;
Expand All @@ -132,7 +132,7 @@ class FusionNode : public rclcpp::Node
// Custom process methods
virtual void preprocess(Msg3D & output_msg);
virtual void fuseOnSingleImage(
const Msg3D & input_msg, const Det2dManager<Msg2D> & det2d, const Msg2D & input_roi_msg,
const Msg3D & input_msg, const Det2dStatus<Msg2D> & det2d, const Msg2D & input_roi_msg,
Msg3D & output_msg) = 0;
virtual void postprocess(Msg3D & output_msg);
virtual void publish(const Msg3D & output_msg);
Expand All @@ -143,7 +143,7 @@ class FusionNode : public rclcpp::Node
tf2_ros::TransformListener tf_listener_;

// 2d detection management
std::vector<Det2dManager<Msg2D>> det2d_list_;
std::vector<Det2dStatus<Msg2D>> det2d_list_;
std::mutex mutex_det2d_flags_;

// camera projection
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class PointPaintingFusionNode : public FusionNode<PointCloudMsgType, RoiMsgType,
void preprocess(PointCloudMsgType & pointcloud_msg) override;

void fuseOnSingleImage(
const PointCloudMsgType & input_pointcloud_msg, const Det2dManager<RoiMsgType> & det2d,
const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus<RoiMsgType> & det2d,
const RoiMsgType & input_roi_msg, PointCloudMsgType & painted_pointcloud_msg) override;

void postprocess(PointCloudMsgType & painted_pointcloud_msg) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class RoiClusterFusionNode : public FusionNode<ClusterMsgType, RoiMsgType, Clust
void publish(const ClusterMsgType & output_msg) override;

void fuseOnSingleImage(
const ClusterMsgType & input_cluster_msg, const Det2dManager<RoiMsgType> & det2d,
const ClusterMsgType & input_cluster_msg, const Det2dStatus<RoiMsgType> & det2d,
const RoiMsgType & input_roi_msg, ClusterMsgType & output_cluster_msg) override;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,11 @@ class RoiDetectedObjectFusionNode : public FusionNode<DetectedObjects, RoiMsgTyp
void preprocess(DetectedObjects & output_msg) override;

void fuseOnSingleImage(
const DetectedObjects & input_object_msg, const Det2dManager<RoiMsgType> & det2d,
const DetectedObjects & input_object_msg, const Det2dStatus<RoiMsgType> & det2d,
const RoiMsgType & input_roi_msg, DetectedObjects & output_object_msg) override;

std::map<std::size_t, DetectedObjectWithFeature> generateDetectedObjectRoIs(
const DetectedObjects & input_object_msg, const Det2dManager<RoiMsgType> & det2d,
const DetectedObjects & input_object_msg, const Det2dStatus<RoiMsgType> & det2d,
const Eigen::Affine3d & object2camera_affine);

void fuseObjectsOnImage(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class RoiPointCloudFusionNode : public FusionNode<PointCloudMsgType, RoiMsgType,
void postprocess(PointCloudMsgType & pointcloud_msg) override;

void fuseOnSingleImage(
const PointCloudMsgType & input_pointcloud_msg, const Det2dManager<RoiMsgType> & det2d,
const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus<RoiMsgType> & det2d,
const RoiMsgType & input_roi_msg, PointCloudMsgType & output_pointcloud_msg) override;

void publish(const PointCloudMsgType & output_msg) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloudMsgType, Image,
void postprocess(PointCloudMsgType & pointcloud_msg) override;

void fuseOnSingleImage(
const PointCloudMsgType & input_pointcloud_msg, const Det2dManager<Image> & det2d,
const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus<Image> & det2d,
const Image & input_mask, PointCloudMsgType & output_pointcloud_msg) override;

inline void copyPointCloud(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ FusionNode<Msg3D, Msg2D, ExportObj>::FusionNode(
approx_grid_cell_w_size_ = declare_parameter<float>("approximation_grid_cell_width");
approx_grid_cell_h_size_ = declare_parameter<float>("approximation_grid_cell_height");

// camera manager initialization
// 2d detection status initialization
det2d_list_.resize(rois_number_);
for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) {
det2d_list_.at(roi_i).mtx_ptr = std::make_unique<std::mutex>();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -255,7 +255,7 @@ void PointPaintingFusionNode::preprocess(PointCloudMsgType & painted_pointcloud_

void PointPaintingFusionNode::fuseOnSingleImage(
__attribute__((unused)) const PointCloudMsgType & input_pointcloud_msg,
const Det2dManager<RoiMsgType> & det2d, const RoiMsgType & input_roi_msg,
const Det2dStatus<RoiMsgType> & det2d, const RoiMsgType & input_roi_msg,
PointCloudMsgType & painted_pointcloud_msg)
{
if (painted_pointcloud_msg.data.empty() || painted_pointcloud_msg.fields.empty()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ void RoiClusterFusionNode::preprocess(ClusterMsgType & output_cluster_msg)
}

void RoiClusterFusionNode::fuseOnSingleImage(
const ClusterMsgType & input_cluster_msg, const Det2dManager<RoiMsgType> & det2d,
const ClusterMsgType & input_cluster_msg, const Det2dStatus<RoiMsgType> & det2d,
const RoiMsgType & input_roi_msg, ClusterMsgType & output_cluster_msg)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg)
}

void RoiDetectedObjectFusionNode::fuseOnSingleImage(
const DetectedObjects & input_object_msg, const Det2dManager<RoiMsgType> & det2d,
const DetectedObjects & input_object_msg, const Det2dStatus<RoiMsgType> & det2d,
const RoiMsgType & input_roi_msg, DetectedObjects & output_object_msg __attribute__((unused)))
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
Expand Down Expand Up @@ -116,7 +116,7 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage(

std::map<std::size_t, DetectedObjectWithFeature>
RoiDetectedObjectFusionNode::generateDetectedObjectRoIs(
const DetectedObjects & input_object_msg, const Det2dManager<RoiMsgType> & det2d,
const DetectedObjects & input_object_msg, const Det2dStatus<RoiMsgType> & det2d,
const Eigen::Affine3d & object2camera_affine)
{
std::unique_ptr<ScopedTimeTrack> st_ptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ void RoiPointCloudFusionNode::postprocess(PointCloudMsgType & pointcloud_msg)
}
}
void RoiPointCloudFusionNode::fuseOnSingleImage(
const PointCloudMsgType & input_pointcloud_msg, const Det2dManager<RoiMsgType> & det2d,
const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus<RoiMsgType> & det2d,
const RoiMsgType & input_roi_msg,
__attribute__((unused)) PointCloudMsgType & output_pointcloud_msg)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ void SegmentPointCloudFusionNode::postprocess(PointCloudMsgType & pointcloud_msg
}

void SegmentPointCloudFusionNode::fuseOnSingleImage(
const PointCloudMsgType & input_pointcloud_msg, const Det2dManager<Image> & det2d,
const PointCloudMsgType & input_pointcloud_msg, const Det2dStatus<Image> & det2d,
[[maybe_unused]] const Image & input_mask,
__attribute__((unused)) PointCloudMsgType & output_cloud)
{
Expand Down

0 comments on commit 3c73ba9

Please sign in to comment.