$search
00001 00034 #include <ros/ros.h> 00035 #include <opencv/cv.h> 00036 #include <opencv/highgui.h> 00037 #include "cv_bridge/CvBridge.h" 00038 #include "sensor_msgs/Image.h" 00039 #include "sensor_msgs/CameraInfo.h" 00040 #include <pr2_interactive_segmentation/depthImage.h> 00041 00042 00043 00044 00045 00046 int main(int argc, char **argv) { 00047 ros::init(argc, argv, "robot_self_filter_test"); 00048 00049 ros::NodeHandle nh; 00050 ros::ServiceClient svc = nh.serviceClient<pr2_interactive_segmentation::depthImage>("getDepthImage"); 00051 00052 sensor_msgs::CvBridge bridge_mask; 00053 00054 00055 cvNamedWindow("alpha",1); 00056 00057 while (nh.ok()){ 00058 00059 pr2_interactive_segmentation::depthImage servicecall; 00060 svc.call(servicecall); 00061 00062 sensor_msgs::Image mask = servicecall.response.depth_image; 00063 00064 printf("width %d height %d", mask.width, mask.height); 00065 00066 // for (int y=0; y<mask.height; ++y){ 00067 // for (int x=0; x< mask.width; ++x){ 00068 // printf("%d ", mask.data[y*mask.width + x]); 00069 // } 00070 // printf (" >>>>endl line %d<<<<<\n", y); 00071 // } 00072 sensor_msgs::ImageConstPtr maskptr = boost::make_shared<sensor_msgs::Image>(boost::ref(servicecall.response.depth_image)); 00073 // cv::Ptr<IplImage> iplimagemask = bridge_mask.imgMsgToCv(boost::make_shared<sensor_msgs::Image>(mask), "passthrough"); 00074 IplImage* iplimagemask = bridge_mask.imgMsgToCv(maskptr, "passthrough"); 00075 00076 cvShowImage("alpha", iplimagemask); 00077 00078 00079 cvWaitKey(); 00080 00081 00082 00083 00084 00085 } 00086 00087 00088 }