37 #ifndef POSEDETECTION_MSGS_FEATURE0D_TO_IMAGE_H_ 38 #define POSEDETECTION_MSGS_FEATURE0D_TO_IMAGE_H_ 41 #include <sensor_msgs/Image.h> 42 #include <posedetection_msgs/ImageFeature0D.h> 44 #include <opencv/cv.hpp> 45 #include <opencv2/highgui/highgui.hpp> 46 #include <boost/shared_ptr.hpp> 56 const std::vector<float> positions,
57 const std::vector<float> scales,
58 const std::vector<float> orientations)
62 for(
size_t i = 0; i < positions.size()/2; ++i) {
63 float scale = i < scales.size() ? scales[i] : 10.0;
64 cv::Point center = cv::Point(positions[2*i+0], positions[2*i+1]);
65 cv::circle(dst, center, scale, CV_RGB(0,255,0));
66 if( i < orientations.size() ) {
68 cv::Point end_pt = cv::Point(center.x+std::cos(orientations[i])*scale,
69 center.y+std::sin(orientations[i])*scale);
70 cv::line(dst, center, end_pt, CV_RGB(255,0,0));
84 posedetection_msgs::Feature0D
92 void imagefeature_cb(
const posedetection_msgs::ImageFeature0DConstPtr& msg_ptr);
94 const posedetection_msgs::Feature0DConstPtr& feature_msg);
message_filters::Subscriber< posedetection_msgs::Feature0D > _sub_feature
void imagefeature_cb(const posedetection_msgs::ImageFeature0DConstPtr &msg_ptr)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > _sync
ros::Subscriber _sub_imagefeature
virtual ~Feature0DToImage()
cv::Mat draw_features(const cv::Mat src, const std::vector< float > positions, const std::vector< float > scales, const std::vector< float > orientations)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, posedetection_msgs::Feature0D > SyncPolicy
message_filters::Subscriber< sensor_msgs::Image > _sub_image