Skip to content

Commit

Permalink
update detector2d_base
Browse files Browse the repository at this point in the history
  • Loading branch information
Ar-Ray-code committed Mar 30, 2024
1 parent e30b85f commit 3feac98
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ class Detector
virtual vision_msgs::msg::Detection2DArray detect(const cv::Mat & image) = 0;
virtual ~Detector() {}

private:
cv::Mat3b draw_bboxes(
const cv::Mat & frame,
const vision_msgs::msg::Detection2DArray & boxes)
Expand Down
2 changes: 2 additions & 0 deletions detector2d_node/include/detector2d_node/detector2d_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,5 +37,7 @@ class Detector2dNode : public rclcpp::Node
std::shared_ptr<detector2d_base::Detector> detector_;

std::shared_ptr<detector2d_parameters::ParamListener> param_listener_;

detector2d_parameters::Detector2dParam params_;
};
}
10 changes: 9 additions & 1 deletion detector2d_node/src/detector2d_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ Detector2dNode::Detector2dNode(const rclcpp::NodeOptions & options)
{
this->param_listener_ = std::make_shared<detector2d_parameters::ParamListener>(
this->get_node_parameters_interface());
const auto params = this->param_listener_->get_params();
this->params_ = this->param_listener_->get_params();

try {
this->detector_ = this->detection_loader_.createSharedInstance(
Expand Down Expand Up @@ -52,6 +52,14 @@ void Detector2dNode::image_callback(const sensor_msgs::msg::Image::SharedPtr msg
vision_msgs::msg::Detection2DArray bboxes =
this->detector_->detect(cv_bridge::toCvShare(msg, "bgr8")->image);
bboxes.header = msg->header;

if (this->params_.debug) {
cv::imshow("detector", this->draw_bboxes(image, bboxes));
auto key = cv::waitKey(1);
if (key == 27) {
rclcpp::shutdown();
}
}
this->pose_pub_->publish(bboxes);
}
} // namespace detector2d_node
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@ class PanelSimpleDetector : public detector2d_base::Detector
Detection2DArray detect(const cv::Mat &) override;

private:
void draw(const cv::Mat &, const CenterPoints &, const std::string &);
CenterPoints get_center_points(const Contours &);
CenterPoints merge_center_points(const CenterPoints &, const int &);

Expand Down
16 changes: 0 additions & 16 deletions detector2d_plugins/src/panel_simple_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,6 @@ Detection2DArray PanelSimpleDetector::detect(const cv::Mat & image)
CenterPoints center_points = get_center_points(contours);
CenterPoints merged_center_points = merge_center_points(center_points, image.cols);

if (debug) {
draw(image, merged_center_points, "merged_center_points");
}

Detection2DArray pose;
for (auto center_point : merged_center_points) {
vision_msgs::msg::Detection2D detection;
Expand All @@ -70,18 +66,6 @@ Detection2DArray PanelSimpleDetector::detect(const cv::Mat & image)
return pose;
}

void PanelSimpleDetector::draw(
const cv::Mat & image, const CenterPoints & center_points,
const std::string & window_name)
{
cv::Mat3b canvas = image.clone();
for (auto center_point : center_points) {
cv::circle(canvas, center_point, 2, cv::Scalar(0, 255, 0), 2);
}
cv::imshow(window_name, canvas);
cv::waitKey(1);
}

CenterPoints PanelSimpleDetector::get_center_points(const Contours & contours)
{
CenterPoints center_points;
Expand Down

0 comments on commit 3feac98

Please sign in to comment.