3 #include <opencv2/highgui/highgui.hpp> 4 #include <cv_bridge/cv_bridge.h> 10 cv::imshow(
"view", cv_bridge::toCvShare(msg,
"bgr8")->image);
13 catch (cv_bridge::Exception& e)
15 ROS_ERROR(
"Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
19 int main(
int argc,
char **argv)
23 cv::namedWindow(
"view");
24 cv::startWindowThread();
28 cv::destroyWindow(
"view");
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...
int main(int argc, char **argv)
Advertise and subscribe to image topics.