Skip to content

Commit

Permalink
Merge pull request #44 from rodperex/main
Browse files Browse the repository at this point in the history
isDetected updated
  • Loading branch information
rodperex authored Jul 17, 2024
2 parents b2e1374 + 94b5705 commit 9256e7c
Show file tree
Hide file tree
Showing 3 changed files with 52 additions and 4 deletions.
10 changes: 10 additions & 0 deletions bt_nodes/perception/include/perception/IsDetected.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@
#include "perception_system_interfaces/msg/detection_array.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_cascade_lifecycle/rclcpp_cascade_lifecycle.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "cv_bridge/cv_bridge.h"

namespace perception
{
Expand All @@ -58,12 +60,14 @@ class IsDetected : public BT::ConditionNode
BT::InputPort<std::string>("color", "unknown", "color"),
BT::InputPort<std::string>("gesture", "unknown", "gesture"),
BT::InputPort<std::string>("pose", "unknown", "pose"),
BT::InputPort<bool>("pub_bb_img"),

BT::OutputPort<std::vector<std::string>>("frames"),
BT::OutputPort<std::string>("best_detection")});
}

private:
void image_callback(const sensor_msg::msg::Image::SharedPtr msg);
std::shared_ptr<rclcpp_cascade_lifecycle::CascadeLifecycleNode> node_;
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;

Expand All @@ -83,6 +87,12 @@ class IsDetected : public BT::ConditionNode
std::map<std::string, cv::Scalar> colors_;
std::map<std::string, std::vector<int>> gestures_;
std::map<int, std::string> pose_names_;

bool pub_bb_img_{false};
rclcpp::Publisher<sensor_msg::msg::Image>::SharedPtr bb_img_pub_;
rclcpp::Subscription<sensor_msg::msg::Image>::SharedPtr img_sub_;

cv::Mat last_image_;
};

} // namespace perception
Expand Down
44 changes: 41 additions & 3 deletions bt_nodes/perception/src/perception/IsDetected.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,19 @@ IsDetected::IsDetected(const std::string & xml_tag_name, const BT::NodeConfigura
getInput("order", order_);
getInput("max_depth", max_depth_);
getInput("person_id", person_id_);
getInput("pub_bb_img", pub_bb_img_);

if (pub_bb_img_) {
pub_bb_img_ = node_->create_publisher<sensor_msgs::msg::Image>(
"/bb_img_best_detection", 10);
img_sub_ = node_->create_subscription<sensor_msgs::msg::Image>(
"/camera/color/image_raw", 10,
std::bind(&IsDetected::image_callback, this, _1));
} else {
pub_bb_img_ = nullptr;
img_sub_ = nullptr;
}

}

BT::NodeStatus IsDetected::tick()
Expand Down Expand Up @@ -96,7 +109,7 @@ BT::NodeStatus IsDetected::tick()
return BT::NodeStatus::FAILURE;
}

RCLCPP_DEBUG(node_->get_logger(), "[IsDetected] Processing %d detections...", detections.size());
RCLCPP_DEBUG(node_->get_logger(), "[IsDetected] Processing %ld detections...", detections.size());

if (order_ == "color") {
// sorted by the distance to the color person we should sort it by distance and also by left to right or right to left
Expand Down Expand Up @@ -220,12 +233,26 @@ BT::NodeStatus IsDetected::tick()
RCLCPP_INFO(node_->get_logger(), "[IsDetected] %d detections after filter", frames_.size());
}

// auto pub = node_->create_publisher<sensor_msgs::msg::Image>(
// "/object_detected", 10);


// pub->publish(detections[0].image);

setOutput("best_detection", detections[0].class_name);

if (pub_bb_img_) {
cv::Point center2d(
detections[0].center2d.x, detections[0].center2d.y);

// cv::circle(last_image_, center2d, 5, cv::Scalar(0, 0, 255), -1);

cv::putText(
last_image_, "X", center2d, cv::FONT_HERSHEY_SIMPLEX, 1,
cv::Scalar(0, 0, 255), 2);

auto msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", last_image_).toImageMsg();
pub_bb_img_->publish(*msg);
}

RCLCPP_DEBUG(node_->get_logger(), "[IsDetected] Detections sorted");
// implement more sorting methods

Expand All @@ -238,6 +265,17 @@ BT::NodeStatus IsDetected::tick()
return BT::NodeStatus::SUCCESS;
}

void IsDetected::image_callback(const sensor_msgs::msg::Image::SharedPtr msg)
{
cv_bridge::CvImagePtr image_rgb_ptr;
try {
image_rgb_ptr = cv_bridge::toCvCopy(msg->source_img, sensor_msgs::image_encodings::BGR8);
} catch (cv_bridge::Exception & e) {
RCLCPP_ERROR(get_logger(), "cv_bridge exception: %s", e.what());
return;
}
last_image_ = image_rgb_ptr->image;

} // namespace perception

BT_REGISTER_NODES(factory) {
Expand Down
2 changes: 1 addition & 1 deletion bt_nodes/perception/src/perception/count_people.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ BT::NodeStatus CountPeople::tick()
return BT::NodeStatus::SUCCESS;
}

RCLCPP_INFO(node_->get_logger(), "[CountPeople] Processing %d detections...", detections.size());
RCLCPP_INFO(node_->get_logger(), "[CountPeople] Processing %ld detections...", detections.size());
auto entity_counter = 0;
for (auto it = detections.begin(); it != detections.end() && entity_counter < max_entities_; ) {
auto const & detection = *it;
Expand Down

0 comments on commit 9256e7c

Please sign in to comment.