cmvision_color_blob_finder.h
Go to the documentation of this file.
00001 /*
00002  *  Player - One Hell of a Robot Server
00003  *  Copyright (C) 2000
00004  *     Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
00005  *     Andrew Martignoni III
00006  *
00007  *  This program is free software; you can redistribute it and/or modify
00008  *  it under the terms of the GNU General Public License as published by
00009  *  the Free Software Foundation; either version 2 of the License, or
00010  *  (at your option) any later version.
00011  *
00012  *  This program is distributed in the hope that it will be useful,
00013  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00014  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00015  *  GNU General Public License for more details.
00016  *
00017  *  You should have received a copy of the GNU General Public License
00018  *  along with this program; if not, write to the Free Software
00019  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00020  *
00021  */
00022 /*
00023  * Uses CMVision to retrieve the blob data
00024  */
00025 // author Andy Martignoni III, Brian Gerkey, Brendan Burns, Ben Grocholsky, Brad Kratochvil
00026 
00027 #include <ros/ros.h>
00028 #include <sensor_msgs/Image.h>
00029 
00030 #include <opencv/cv.h>
00031 #include <cv_bridge/CvBridge.h>
00032 
00033 #include <cmvision/Blobs.h>
00034 #include "conversions.h"
00035 #include "cmvision.h"
00036 #include "capture.h"
00037 
00038 #define CMV_NUM_CHANNELS CMV_MAX_COLORS
00039 #define CMV_HEADER_SIZE 4*CMV_NUM_CHANNELS
00040 #define CMV_BLOB_SIZE 16
00041 #define CMV_MAX_BLOBS_PER_CHANNEL 10
00042 
00043 #define DEFAULT_CMV_WIDTH CMV_DEFAULT_WIDTH
00044 #define DEFAULT_CMV_HEIGHT CMV_DEFAULT_HEIGHT
00045 
00046 namespace color_blob_track
00047 {
00048 
00049 class CMVisionColorBlobFinder
00050 {
00051 public:
00052 
00054         CMVisionColorBlobFinder();
00055 
00057         virtual ~CMVisionColorBlobFinder();
00058 
00063         bool initialize(ros::NodeHandle &node_handle);
00064 
00066         void imageCB(const sensor_msgs::ImageConstPtr& msg);
00067 
00068 private:
00069 
00070         ros::Publisher blob_publisher_;
00071         ros::Subscriber image_subscriber_;
00072 
00073         // sensor_msgs::Image image;
00074         sensor_msgs::CvBridge image_bridge_;
00075 
00076         bool debug_on_;
00077   int region_area_; 
00078         uint16_t width_;
00079         uint16_t height_;
00080         std::string color_filename_;
00081         uint8_t *uyvy_image_;
00082 
00083         unsigned int blob_count_;
00084 
00085         CMVision *vision_;
00086 
00087         cmvision::Blobs blob_message_;
00088 
00089         bool mean_shift_on_;
00090         double spatial_radius_;
00091         double color_radius_;
00092 
00093 };
00094 
00095 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


image_algos
Author(s): Dejan Pangercic
autogenerated on Thu May 23 2013 18:41:31