my_subscriber.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <opencv2/highgui/highgui.hpp>
4 #include <cv_bridge/cv_bridge.h>
5 
6 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
7 {
8  try
9  {
10  cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image);
11  cv::waitKey(10);
12  }
13  catch (cv_bridge::Exception& e)
14  {
15  ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
16  }
17 }
18 
19 int main(int argc, char **argv)
20 {
21  ros::init(argc, argv, "image_listener");
22  ros::NodeHandle nh;
23  cv::namedWindow("view");
24  cv::startWindowThread();
26  image_transport::Subscriber sub = it.subscribe("camera/image", 1, imageCallback);
27  ros::spin();
28  cv::destroyWindow("view");
29 }
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for arbitrary boost::function object.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Manages a subscription callback on a specific topic that can be interpreted as an Image topic...
Definition: subscriber.h:62
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
Advertise and subscribe to image topics.
#define ROS_ERROR(...)


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Apr 4 2020 03:14:58