Skip to content
Open
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
55 changes: 55 additions & 0 deletions src/damian_package/src/damian_node.cpp
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We should delete this file from this branch, it's not relevant to the merge request

Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
#include <rclcpp/rclcpp.hpp>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>

class DamianNode : public rclcpp::Node {
public:
DamianNode() : Node("damian_node") {
RCLCPP_INFO(this->get_logger(), "DamianNode started!");
processImage(); // Directly process `image.jpg`
}

private:
void processImage() {
// Load the image
cv::Mat image = cv::imread("image.jpg");

if (image.empty()) {
RCLCPP_ERROR(this->get_logger(), "Failed to load image.jpg!");
return;
}

RCLCPP_INFO(this->get_logger(), "Processing image.jpg...");

// Save the original image
cv::imwrite("original_image.jpg", image);

// Apply grayscale conversion
cv::Mat processed_image;
cv::cvtColor(image, processed_image, cv::COLOR_BGR2GRAY);

// Save processed image
cv::imwrite("processed_image.jpg", processed_image);

// Display images
RCLCPP_INFO(this->get_logger(), "Saving images (GUI disabled)...");

cv::imwrite("original_image.jpg", image);
cv::imwrite("processed_image.jpg", processed_image);

RCLCPP_INFO(this->get_logger(), "Images saved successfully!");


RCLCPP_INFO(this->get_logger(), "Image processing completed!");
}
};

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<DamianNode>();
rclcpp::shutdown();
return 0;
}
115 changes: 115 additions & 0 deletions src/damian_package/src/target_selector_node.cpp
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let's move all this code to a package dedicated specifically to target selection. You should make a new package called target_selection and put this file inside the source folder of that. Refer to onboarding or any other resources you might need (ChatGPT) if needed. Once moved, this folder should be deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
#include "rclcpp/rclcpp.hpp"
#include "vision_msgs/msg/detection2_d_array.hpp"
#include "vision_msgs/msg/detection2_d.hpp"
#include "std_msgs/msg/header.hpp"
#include "visualization_msgs/msg/marker.hpp"
#include <limits>
#include <cmath>

class TargetSelectorNode : public rclcpp::Node
{
public:
TargetSelectorNode() : Node("target_selector_node")
{
detection_sub_ = this->create_subscription<vision_msgs::msg::Detection2DArray>(
"/detections", 10,
std::bind(&TargetSelectorNode::detection_callback, this, std::placeholders::_1));

target_pub_ = this->create_publisher<vision_msgs::msg::Detection2D>("/target", 10);

marker_pub_ = this->create_publisher<visualization_msgs::msg::Marker>("/target_marker", 10);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What is the purpose of this publisher? What is a marker?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The target_pub_ publishes the best detection (closest to the center of the image) as a vision_msgs::msg::Detection2D to the /target topic. This allows other nodes in the system (e.g., decision-making, aiming, or tracking nodes) to focus only on that selected target instead of processing all detections. And the marker was for RViz visualization, but I can remove it.


// Set your actual camera resolution here (update if different)
image_width_ = 1280.0;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can we make these ros params that default to 1280 and 720

image_height_ = 720.0;
center_x_ = image_width_ / 2.0;
center_y_ = image_height_ / 2.0;

RCLCPP_INFO(this->get_logger(), "Target Selector Node initialized.");
}

private:
rclcpp::Subscription<vision_msgs::msg::Detection2DArray>::SharedPtr detection_sub_;
rclcpp::Publisher<vision_msgs::msg::Detection2D>::SharedPtr target_pub_;
rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr marker_pub_;

double image_width_;
double image_height_;
double center_x_;
double center_y_;

void detection_callback(const vision_msgs::msg::Detection2DArray::SharedPtr msg)
{
if (msg->detections.empty())
{
RCLCPP_DEBUG(this->get_logger(), "No detections received.");
return;
}

double min_distance = std::numeric_limits<double>::max();
vision_msgs::msg::Detection2D best_detection;

for (const auto &detection : msg->detections)
{
double dx = detection.bbox.center.position.x - center_x_;
double dy = detection.bbox.center.position.y - center_y_;
double distance = dx * dx + dy * dy;

if (distance < min_distance)
{
min_distance = distance;
best_detection = detection;
}
}

// Set header stamp and frame ID
best_detection.header.stamp = this->get_clock()->now();
best_detection.header.frame_id = msg->header.frame_id;

target_pub_->publish(best_detection);

RCLCPP_INFO(this->get_logger(), "Published best detection at (%.2f, %.2f)",
best_detection.bbox.center.position.x,
best_detection.bbox.center.position.y);

publish_marker(best_detection);
}

void publish_marker(const vision_msgs::msg::Detection2D &detection)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you explain what this code is doing?

{
visualization_msgs::msg::Marker marker;
marker.header.frame_id = detection.header.frame_id;
marker.header.stamp = this->get_clock()->now();
marker.ns = "target_selector";
marker.id = 0;
marker.type = visualization_msgs::msg::Marker::SPHERE;
marker.action = visualization_msgs::msg::Marker::ADD;

marker.pose.position.x = detection.bbox.center.position.x;
marker.pose.position.y = detection.bbox.center.position.y;
marker.pose.position.z = 0.0;
marker.pose.orientation.w = 1.0;

marker.scale.x = 20.0;
marker.scale.y = 20.0;
marker.scale.z = 1.0;

marker.color.r = 1.0f;
marker.color.g = 0.0f;
marker.color.b = 0.0f;
marker.color.a = 1.0f;

marker.lifetime = rclcpp::Duration::from_seconds(0.5);

marker_pub_->publish(marker);
}
};

int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<TargetSelectorNode>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}