Project

General

Profile

Revision 32006eb7

ID32006eb7cceaf9bbd39d44169a7eaa8a9fbda929

Added by Thomas Mullins about 12 years ago

Fixed segfault in opencvdetect

View differences:

vision/src/opencvdetect.cpp
35 35

  
36 36
void target_cb(const sensor_msgs::Image orig) {
37 37

  
38
  printf("beginning callback \n");
39 38
  tf::TransformListener listener;
40 39
  geometry_msgs::Point point;
41 40
  tf::StampedTransform transform;
......
58 57
  }
59 58

  
60 59
  // detect blob
61
  IplImage* input;
62
  input = new IplImage;
63
  *input = cv_ptr->image;
60
  IplImage input(cv_ptr->image);
64 61

  
65 62
  IplImage* img;
66 63
  IplImage *hsv_img;
......
71 68
  
72 69
  // Initialize images, allocate memory
73 70

  
74
  img = cvCloneImage(input);
71
  img = cvCloneImage(&input);
75 72
  hsv_img = cvCloneImage(img);
76
  bw_img = cvCreateImage(cvSize(img->width, img->height), 8, 1);;
73
  bw_img = cvCreateImage(cvSize(img->width, img->height), 8, 1);
77 74
  i1 = cvCreateImage(cvSize(img->width, img->height), 8, 1);
78 75

  
79
  printf("Initialized!\n");
80
  printf("%x\n", input);
81
  printf("%x\n", img);
82
  printf("%x\n", hsv_img);
83
  printf("%x\n", bw_img);
84
  printf("%x\n", i1);
85 76
  // Smooth input image using a Gaussian filter, assign HSV, BW image
86
  cvSmooth(input, img, CV_GAUSSIAN, 7, 9, 0 ,0);
87
  printf("1");
77
  cvSmooth(&input, img, CV_GAUSSIAN, 7, 9, 0 ,0);
88 78
  cvCvtColor(img, bw_img, CV_RGB2GRAY);
89
  printf("2");
90 79
  cvCvtColor(img, hsv_img, CV_RGB2HSV);
91
  printf("3");
92 80

  
93 81
  // Simple filter that creates a mask whose color is near orange in i1
94 82
  for(int i = 0; i < hsv_img->height; i++) {
......
103 91
      }
104 92
  }
105 93

  
106
  printf("4");
107 94
  // Detect Blobs using the mask and a threshold for area. Sort blobs according to area
108 95
  blobs = CBlobResult(bw_img, i1, 100/*, true*/);
109 96
  blobs.Filter(blobs, B_INCLUDE, CBlobGetArea(), B_GREATER, 500);
......
129 116
  blob_image.data = *(img->imageData); */
130 117
  img_pub.publish(blob_image);  
131 118

  
132
  // Clean up 
119
  // Clean up
133 120
  cvReleaseImage(&i1);
134 121
  cvReleaseImage(&bw_img);
135 122
  cvReleaseImage(&hsv_img);
136 123
  cvReleaseImage(&img);
137
  cvReleaseImage(&input);
138 124

  
139 125
  //int comX; 
140 126
  //int comY;
......
158 144
    
159 145
//  pub.publish(origPoint);
160 146

  
161
  printf("Ending callback\n");
162

  
163 147
}
164 148

  
165 149
void target_cb_test(const sensor_msgs::Image image){

Also available in: Unified diff