feature0d_to_image.cpp
Go to the documentation of this file.
1 // vim: set tabstop=4 shiftwidth=4:
2 // Copyright (C) 2008-2009 Rosen Diankov
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
15 #include <ros/node_handle.h>
16 #include <sensor_msgs/Image.h>
17 #include <posedetection_msgs/ImageFeature0D.h>
18 
19 #include <opencv2/highgui/highgui.hpp>
20 #include <boost/shared_ptr.hpp>
21 
22 #include <cv_bridge/cv_bridge.h>
24 
25 namespace posedetection_msgs
26 {
28  {
29  ros::NodeHandle local_nh("~");
30 
31  _pub = _node.advertise<sensor_msgs::Image>(local_nh.resolveName("output"), 1);
32  _sub_image.subscribe(_node, "image", 1);
33  _sub_feature.subscribe(_node, "Feature0D", 1);
34  _sync = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
35  _sync->connectInput(_sub_image, _sub_feature);
36  _sync->registerCallback(boost::bind(&Feature0DToImage::imagefeature_cb, this,
39  }
41 
42  void Feature0DToImage::imagefeature_cb(const sensor_msgs::ImageConstPtr& image_msg,
43  const posedetection_msgs::Feature0DConstPtr& feature_msg)
44  {
45  cv_bridge::CvImagePtr cv_ptr;
46  try {
47  cv_ptr = cv_bridge::toCvCopy(image_msg, "bgr8");
48  cv::Mat image = draw_features(cv_ptr->image,
49  feature_msg->positions,
50  feature_msg->scales,
51  feature_msg->orientations);
52  _pub.publish(cv_bridge::CvImage(cv_ptr->header, "bgr8", image));
53  } catch (cv_bridge::Exception& error) {
54  ROS_WARN("bad frame");
55  return;
56  }
57  }
58 
59  void Feature0DToImage::imagefeature_cb(const posedetection_msgs::ImageFeature0DConstPtr& msg_ptr)
60  {
61  cv_bridge::CvImagePtr cv_ptr;
62  try {
63  cv_ptr = cv_bridge::toCvCopy(msg_ptr->image, "bgr8");
64  cv::Mat image = draw_features(cv_ptr->image,
65  msg_ptr->features.positions,
66  msg_ptr->features.scales,
67  msg_ptr->features.orientations);
68  _pub.publish(cv_bridge::CvImage(cv_ptr->header, "bgr8", image));
69  } catch (cv_bridge::Exception& error) {
70  ROS_WARN("bad frame");
71  return;
72  }
73  }
74 }
75 
76 int main(int argc, char **argv)
77 {
78  ros::init(argc, argv, "feature0d_to_image");
80  ros::spin();
81  return 0;
82 }
83 
node_handle.h
boost::placeholders::_2
boost::arg< 2 > _2
boost::shared_ptr
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
posedetection_msgs::Feature0DToImage::_sync
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > _sync
Definition: feature0d_to_image.h:107
posedetection_msgs::Feature0DToImage::_sub_imagefeature
ros::Subscriber _sub_imagefeature
Definition: feature0d_to_image.h:102
cv_bridge::Exception
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
posedetection_msgs::Feature0DToImage
Definition: feature0d_to_image.h:97
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
posedetection_msgs::Feature0DToImage::_sub_feature
message_filters::Subscriber< posedetection_msgs::Feature0D > _sub_feature
Definition: feature0d_to_image.h:109
posedetection_msgs::draw_features
cv::Mat draw_features(const cv::Mat src, const std::vector< float > positions, const std::vector< float > scales, const std::vector< float > orientations)
Definition: feature0d_to_image.h:76
posedetection_msgs::Feature0DToImage::_pub
ros::Publisher _pub
Definition: feature0d_to_image.h:101
posedetection_msgs::Feature0DToImage::_node
ros::NodeHandle _node
Definition: feature0d_to_image.h:100
boost::placeholders::_1
boost::arg< 1 > _1
ROS_WARN
#define ROS_WARN(...)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
posedetection_msgs::Feature0DToImage::_sub_image
message_filters::Subscriber< sensor_msgs::Image > _sub_image
Definition: feature0d_to_image.h:108
message_filters::Subscriber::subscribe
void subscribe()
feature0d_to_image.h
cv_bridge.h
main
int main(int argc, char **argv)
Definition: feature0d_to_image.cpp:76
cv_bridge::CvImage
posedetection_msgs::Feature0DToImage::~Feature0DToImage
virtual ~Feature0DToImage()
Definition: feature0d_to_image.cpp:40
posedetection_msgs
Definition: feature0d_to_image.h:74
synchronizer.h
posedetection_msgs::Feature0DToImage::Feature0DToImage
Feature0DToImage()
Definition: feature0d_to_image.cpp:27
posedetection_msgs::Feature0DToImage::imagefeature_cb
void imagefeature_cb(const posedetection_msgs::ImageFeature0DConstPtr &msg_ptr)
Definition: feature0d_to_image.cpp:59
ros::spin
ROSCPP_DECL void spin()
ros::NodeHandle


posedetection_msgs
Author(s): Rosen Diankov
autogenerated on Thu May 12 2022 02:07:53