feature0d_view.cpp
Go to the documentation of this file.
1 // Copyright (C) 2008-2009 Rosen Diankov
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 // http://www.apache.org/licenses/LICENSE-2.0
7 //
8 // Unless required by applicable law or agreed to in writing, software
9 // distributed under the License is distributed on an "AS IS" BASIS,
10 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
11 // See the License for the specific language governing permissions and
12 // limitations under the License.
15 #include <ros/node_handle.h>
16 #include <ros/master.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>
23 
24 namespace posedetection_msgs
25 {
27  {
28  std::string topic = _node.resolveName("ImageFeature0D");
29  ros::NodeHandle local_nh("~");
30  local_nh.param("window_name", _window_name, topic);
31  bool autosize;
32  local_nh.param("autosize", autosize, false);
33 
34  _sub = _node.subscribe("ImageFeature0D",1,&Feature0DView::image_cb,this);
35  cv::namedWindow(_window_name.c_str(), autosize ? cv::WINDOW_AUTOSIZE : 0);
36  cv::startWindowThread();
37  }
39 
40  void Feature0DView::image_cb(const posedetection_msgs::ImageFeature0DConstPtr& msg_ptr)
41  {
42  cv_bridge::CvImagePtr cv_ptr;
43  try {
44  cv_ptr = cv_bridge::toCvCopy(msg_ptr->image, "bgr8");
45  cv::Mat image = draw_features(cv_ptr->image,
46  msg_ptr->features.positions,
47  msg_ptr->features.scales,
48  msg_ptr->features.orientations);
49  cv::imshow(_window_name.c_str(), image);
50  }
51  catch (cv_bridge::Exception error) {
52  ROS_WARN("bad frame");
53  return;
54  }
55  }
56 };
57 
58 int main(int argc, char **argv)
59 {
60  ros::init(argc,argv,"feature0d_view");
61  if( !ros::master::check() )
62  return 1;
63 
65  ros::spin();
66  node.reset();
67  return 0;
68 }
ros::master::check
ROSCPP_DECL bool check()
node_handle.h
posedetection_msgs::Feature0DView::_sub
ros::Subscriber _sub
Definition: feature0d_view.h:114
boost::shared_ptr
posedetection_msgs::Feature0DView::~Feature0DView
virtual ~Feature0DView()
Definition: feature0d_view.cpp:38
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
feature0d_view.h
posedetection_msgs::Feature0DView::_window_name
std::string _window_name
Definition: feature0d_view.h:115
cv_bridge::Exception
posedetection_msgs::Feature0DView::image_cb
void image_cb(const posedetection_msgs::ImageFeature0DConstPtr &msg_ptr)
Definition: feature0d_view.cpp:40
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
main
int main(int argc, char **argv)
Definition: feature0d_view.cpp:58
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
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
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())
feature0d_to_image.h
cv_bridge.h
posedetection_msgs
Definition: feature0d_to_image.h:74
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
posedetection_msgs::Feature0DView::Feature0DView
Feature0DView()
Definition: feature0d_view.cpp:26
posedetection_msgs::Feature0DView::_node
ros::NodeHandle _node
Definition: feature0d_view.h:113
ros::spin
ROSCPP_DECL void spin()
master.h
posedetection_msgs::Feature0DView
Definition: feature0d_view.h:78
ros::NodeHandle


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