Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 #include <ros/ros.h>
00011 #include <opencv/cv.h>
00012 #include <opencv/highgui.h>
00013 #include "cv_bridge/cv_bridge.h"
00014 #include "sensor_msgs/Image.h"
00015 #include "sensor_msgs/CameraInfo.h"
00016 #include "camera_self_filter/mask.h"
00017
00018
00019
00020
00021
00022 int main(int argc, char **argv) {
00023 ros::init(argc, argv, "robot_self_filter_test");
00024
00025 ros::NodeHandle nh;
00026 ros::ServiceClient svc = nh.serviceClient<camera_self_filter::mask>("self_mask");
00027
00028 cv::namedWindow("alpha");
00029
00030 while (nh.ok()){
00031
00032 camera_self_filter::mask servicecall;
00033 servicecall.request.header.frame_id = "narrow_stereo_optical_frame";
00034 servicecall.request.header.stamp = ros::Time::now();
00035 svc.call(servicecall);
00036
00037 sensor_msgs::Image mask = servicecall.response.mask_image;
00038
00039 printf("width %d height %d", mask.width, mask.height);
00040
00041 sensor_msgs::ImageConstPtr maskptr = boost::make_shared<sensor_msgs::Image>(boost::ref(servicecall.response.mask_image));
00042 cv_bridge::CvImagePtr cv_ptr;
00043 try
00044 {
00045 cv_ptr = cv_bridge::toCvCopy(maskptr, "passthrough");
00046 }
00047 catch (cv_bridge::Exception& e)
00048 {
00049 ROS_ERROR("cv_bridge exception: %s", e.what());
00050 return 0;
00051 }
00052
00053 cv::imshow("alpha", cv_ptr->image);
00054
00055 cvWaitKey();
00056
00057 }
00058
00059 return 0;
00060 }