28 #include <rclcpp/rclcpp.hpp>    29 #include <find_object_2d/msg/objects_stamped.hpp>    32 #include <image_transport/image_transport.hpp>    33 #include <image_transport/subscriber_filter.hpp>    35 #include <opencv2/opencv.hpp>    43                 Node(
"objects_detected")
    47                 imagePub_ = image_transport::create_publisher(
this, 
"image_with_objects", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
    50                 sub_ = create_subscription<std_msgs::msg::Float32MultiArray>(
"objects", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1), std::bind(&
PrintObjects::objectsDetectedCallback, 
this, std::placeholders::_1));
    54                 objectsSub_.
subscribe(
this, 
"objectsStamped", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
    71                         const std_msgs::msg::Float32MultiArray::ConstSharedPtr msg)
    74                 const std::vector<float> & data = msg->data;
    77                         for(
unsigned int i=0; i<data.size(); i+=12)
    80                                 int id = (int)data[i];
    81                                 float objectWidth = data[i+1];
    82                                 float objectHeight = data[i+2];
    85                                 QTransform qtHomography(data[i+3], data[i+4], data[i+5],
    86                                                                                 data[i+6], data[i+7], data[i+8],
    87                                                                                 data[i+9], data[i+10], data[i+11]);
    89                                 QPointF qtTopLeft = qtHomography.map(QPointF(0,0));
    90                                 QPointF qtTopRight = qtHomography.map(QPointF(objectWidth,0));
    91                                 QPointF qtBottomLeft = qtHomography.map(QPointF(0,objectHeight));
    92                                 QPointF qtBottomRight = qtHomography.map(QPointF(objectWidth,objectHeight));
    94                                 printf(
"Object %d detected, Qt corners at (%f,%f) (%f,%f) (%f,%f) (%f,%f)\n",
    96                                                 qtTopLeft.x(), qtTopLeft.y(),
    97                                                 qtTopRight.x(), qtTopRight.y(),
    98                                                 qtBottomLeft.x(), qtBottomLeft.y(),
    99                                                 qtBottomRight.x(), qtBottomRight.y());
   104                         printf(
"No objects detected.\n");
   108                         const sensor_msgs::msg::Image::ConstSharedPtr imageMsg,
   109                         const find_object_2d::msg::ObjectsStamped::ConstSharedPtr objectsMsg)
   113                         const std::vector<float> & data = objectsMsg->objects.data;
   116                                 for(
unsigned int i=0; i<data.size(); i+=12)
   119                                         int id = (int)data[i];
   120                                         float objectWidth = data[i+1];
   121                                         float objectHeight = data[i+2];
   124                                         cv::Mat cvHomography(3, 3, CV_32F);
   125                                         cvHomography.at<
float>(0,0) = data[i+3];
   126                                         cvHomography.at<
float>(1,0) = data[i+4];
   127                                         cvHomography.at<
float>(2,0) = data[i+5];
   128                                         cvHomography.at<
float>(0,1) = data[i+6];
   129                                         cvHomography.at<
float>(1,1) = data[i+7];
   130                                         cvHomography.at<
float>(2,1) = data[i+8];
   131                                         cvHomography.at<
float>(0,2) = data[i+9];
   132                                         cvHomography.at<
float>(1,2) = data[i+10];
   133                                         cvHomography.at<
float>(2,2) = data[i+11];
   134                                         std::vector<cv::Point2f> inPts, outPts;
   135                                         inPts.push_back(cv::Point2f(0,0));
   136                                         inPts.push_back(cv::Point2f(objectWidth,0));
   137                                         inPts.push_back(cv::Point2f(objectWidth,objectHeight));
   138                                         inPts.push_back(cv::Point2f(0,objectHeight));
   139                                         inPts.push_back(cv::Point2f(objectWidth/2,objectHeight/2));
   140                                         cv::perspectiveTransform(inPts, outPts, cvHomography);
   145                                         img = *imageDepthPtr;
   146                                         std::vector<cv::Point2i> outPtsInt;
   147                                         outPtsInt.push_back(outPts[0]);
   148                                         outPtsInt.push_back(outPts[1]);
   149                                         outPtsInt.push_back(outPts[2]);
   150                                         outPtsInt.push_back(outPts[3]);
   151                                         QColor color(QColor((Qt::GlobalColor)((
id % 10 + 7)==Qt::yellow?Qt::darkYellow:(
id % 10 + 7))));
   152                                         cv::Scalar cvColor(color.red(), color.green(), color.blue());
   153                                         cv::polylines(img.
image, outPtsInt, 
true, cvColor, 3);
   154                                         cv::Point2i center = outPts[4];
   155                                         cv::putText(img.
image, QString(
"(%1, %2)").arg(center.x).arg(center.y).toStdString(), center, cv::FONT_HERSHEY_SIMPLEX, 0.6, cvColor, 2);
   156                                         cv::circle(img.
image, center, 1, cvColor, 3);
   165                         sensor_msgs::msg::Image,
   171         rclcpp::Subscription<std_msgs::msg::Float32MultiArray>::SharedPtr 
sub_;
   176 int main(
int argc, 
char** argv)
   178         rclcpp::init(argc, argv);
   179         rclcpp::spin(std::make_shared<PrintObjects>());
 CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
image_transport::SubscriberFilter imageSub_
void objectsDetectedCallback(const std_msgs::msg::Float32MultiArray::ConstSharedPtr msg)
const std::string & getTransport() const
uint32_t getNumSubscribers() const
image_transport::Publisher imagePub_
void imageObjectsDetectedCallback(const sensor_msgs::msg::Image::ConstSharedPtr imageMsg, const find_object_2d::msg::ObjectsStamped::ConstSharedPtr objectsMsg)
int main(int argc, char **argv)
message_filters::Subscriber< find_object_2d::msg::ObjectsStamped > objectsSub_
sensor_msgs::ImagePtr toImageMsg() const
void publish(const sensor_msgs::Image &message) const
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::sync_policies::ExactTime< sensor_msgs::msg::Image, find_object_2d::msg::ObjectsStamped > MyExactSyncPolicy
rclcpp::Subscription< std_msgs::msg::Float32MultiArray >::SharedPtr sub_