Project

General

Profile

Revision 9262605f

ID9262605f3b5396c97415dd847813ea29b128404d

Added by Nick Stanley about 12 years ago

Now it seg faults but compiles, please check this out if you can help.

View differences:

vision/CMakeLists.txt
23 23

  
24 24
#rosbuild_add_executable(v2v3_converter src/v2v3_converter.cpp)
25 25
rosbuild_add_executable(rviz_interactive_target src/rviz_interactive_target.cpp)
26
<<<<<<< HEAD
27
=======
28 26
rosbuild_add_executable(newConverter src/converteroverwrite.cpp)
29
>>>>>>> master
30 27
rosbuild_add_executable(opencvdetect src/opencvdetect.cpp)
31 28

  
32 29
#common commands for building c++ executables and libraries
......
37 34
#rosbuild_add_executable(example examples/example.cpp)
38 35
#target_link_libraries(example ${PROJECT_NAME})
39 36
target_link_libraries(opencvdetect ${OpenCV_LIBS}) 
37
target_link_libraries(opencvdetect /usr/local/include/cvblobs/libblob.a) 
vision/src/opencvdetect.cpp
13 13
#include </home/nstanley/cvblobs8.3_linux/blob.h>
14 14
#include </home/nstanley/cvblobs8.3_linux/BlobResult.h>
15 15

  
16
using namespace std;
17
using namespace cv;
18

  
16 19
ros::Publisher pub;
17 20
ros::Publisher img_pub;
18 21

  
......
22 25
//int threshold = 25;
23 26

  
24 27
int filter(int r, int g, int b, int threshold) {
25
    int orange[3] = {216, 255, 255}; // Orange in HSV
28
    int orange[3] = {hk,sk,vk}; // Orange in HSV
26 29
    int diff =  (orange[0]-r)*(orange[0]-r) +
27 30
                (orange[1]-g)*(orange[1]-g);
28 31

  
......
36 39
  tf::TransformListener listener;
37 40
  geometry_msgs::Point point;
38 41
  tf::StampedTransform transform;
39

  
40
  int width = orig.width; 
41
  int height = orig.height;
42 42
  /*try {
43 43
    listener.lookupTransform("/camera", "/kinect", ros::Time(0), transform);
44 44
  }
......
47 47
  }*/
48 48

  
49 49
  // convert to OpenCV
50

  
51 50
  sensor_msgs::Image hsvcopy = orig;
52 51
  cv_bridge::CvImagePtr cv_ptr;
53 52
  try{
......
59 58
  }
60 59

  
61 60
  // detect blob
62

  
63 61
  IplImage* input;
62
  input = new IplImage;
64 63
  *input = cv_ptr->image;
65 64

  
66 65
  IplImage* img;
......
69 68
  IplImage* i1;
70 69
  CBlobResult blobs;
71 70
  CBlob blobArea;
72

  
71
  
73 72
  // Initialize images, allocate memory
74 73

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

  
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);
80 85
  // Smooth input image using a Gaussian filter, assign HSV, BW image
81 86
  cvSmooth(input, img, CV_GAUSSIAN, 7, 9, 0 ,0);
87
  printf("1");
82 88
  cvCvtColor(img, bw_img, CV_RGB2GRAY);
89
  printf("2");
83 90
  cvCvtColor(img, hsv_img, CV_RGB2HSV);
91
  printf("3");
84 92

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

  
106
  printf("4");
98 107
  // Detect Blobs using the mask and a threshold for area. Sort blobs according to area
99 108
  blobs = CBlobResult(bw_img, i1, 100/*, true*/);
100 109
  blobs.Filter(blobs, B_INCLUDE, CBlobGetArea(), B_GREATER, 500);

Also available in: Unified diff