Skip to content

Commit 9256e7c

Browse files
authored
Merge pull request #44 from rodperex/main
isDetected updated
2 parents b2e1374 + 94b5705 commit 9256e7c

3 files changed

Lines changed: 52 additions & 4 deletions

File tree

bt_nodes/perception/include/perception/IsDetected.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,8 @@
3434
#include "perception_system_interfaces/msg/detection_array.hpp"
3535
#include "rclcpp/rclcpp.hpp"
3636
#include "rclcpp_cascade_lifecycle/rclcpp_cascade_lifecycle.hpp"
37+
#include "sensor_msgs/msg/image.hpp"
38+
#include "cv_bridge/cv_bridge.h"
3739

3840
namespace perception
3941
{
@@ -58,12 +60,14 @@ class IsDetected : public BT::ConditionNode
5860
BT::InputPort<std::string>("color", "unknown", "color"),
5961
BT::InputPort<std::string>("gesture", "unknown", "gesture"),
6062
BT::InputPort<std::string>("pose", "unknown", "pose"),
63+
BT::InputPort<bool>("pub_bb_img"),
6164

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

6669
private:
70+
void image_callback(const sensor_msg::msg::Image::SharedPtr msg);
6771
std::shared_ptr<rclcpp_cascade_lifecycle::CascadeLifecycleNode> node_;
6872
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
6973

@@ -83,6 +87,12 @@ class IsDetected : public BT::ConditionNode
8387
std::map<std::string, cv::Scalar> colors_;
8488
std::map<std::string, std::vector<int>> gestures_;
8589
std::map<int, std::string> pose_names_;
90+
91+
bool pub_bb_img_{false};
92+
rclcpp::Publisher<sensor_msg::msg::Image>::SharedPtr bb_img_pub_;
93+
rclcpp::Subscription<sensor_msg::msg::Image>::SharedPtr img_sub_;
94+
95+
cv::Mat last_image_;
8696
};
8797

8898
} // namespace perception

bt_nodes/perception/src/perception/IsDetected.cpp

Lines changed: 41 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,19 @@ IsDetected::IsDetected(const std::string & xml_tag_name, const BT::NodeConfigura
6666
getInput("order", order_);
6767
getInput("max_depth", max_depth_);
6868
getInput("person_id", person_id_);
69+
getInput("pub_bb_img", pub_bb_img_);
70+
71+
if (pub_bb_img_) {
72+
pub_bb_img_ = node_->create_publisher<sensor_msgs::msg::Image>(
73+
"/bb_img_best_detection", 10);
74+
img_sub_ = node_->create_subscription<sensor_msgs::msg::Image>(
75+
"/camera/color/image_raw", 10,
76+
std::bind(&IsDetected::image_callback, this, _1));
77+
} else {
78+
pub_bb_img_ = nullptr;
79+
img_sub_ = nullptr;
80+
}
81+
6982
}
7083

7184
BT::NodeStatus IsDetected::tick()
@@ -96,7 +109,7 @@ BT::NodeStatus IsDetected::tick()
96109
return BT::NodeStatus::FAILURE;
97110
}
98111

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

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

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

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

228240
setOutput("best_detection", detections[0].class_name);
241+
242+
if (pub_bb_img_) {
243+
cv::Point center2d(
244+
detections[0].center2d.x, detections[0].center2d.y);
245+
246+
// cv::circle(last_image_, center2d, 5, cv::Scalar(0, 0, 255), -1);
247+
248+
cv::putText(
249+
last_image_, "X", center2d, cv::FONT_HERSHEY_SIMPLEX, 1,
250+
cv::Scalar(0, 0, 255), 2);
251+
252+
auto msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", last_image_).toImageMsg();
253+
pub_bb_img_->publish(*msg);
254+
}
255+
229256
RCLCPP_DEBUG(node_->get_logger(), "[IsDetected] Detections sorted");
230257
// implement more sorting methods
231258

@@ -238,6 +265,17 @@ BT::NodeStatus IsDetected::tick()
238265
return BT::NodeStatus::SUCCESS;
239266
}
240267

268+
void IsDetected::image_callback(const sensor_msgs::msg::Image::SharedPtr msg)
269+
{
270+
cv_bridge::CvImagePtr image_rgb_ptr;
271+
try {
272+
image_rgb_ptr = cv_bridge::toCvCopy(msg->source_img, sensor_msgs::image_encodings::BGR8);
273+
} catch (cv_bridge::Exception & e) {
274+
RCLCPP_ERROR(get_logger(), "cv_bridge exception: %s", e.what());
275+
return;
276+
}
277+
last_image_ = image_rgb_ptr->image;
278+
241279
} // namespace perception
242280

243281
BT_REGISTER_NODES(factory) {

bt_nodes/perception/src/perception/count_people.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,7 @@ BT::NodeStatus CountPeople::tick()
8989
return BT::NodeStatus::SUCCESS;
9090
}
9191

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

0 commit comments

Comments
 (0)