object_segmentation_gui::ObjectSegmenter Class Reference

#include <object_segmenter.h>

List of all members.

Classes

struct  Action
struct  Box2D

Public Types

enum  ActionType {
  PAUSE, RESET, CLICK, REGION,
  STOP, GRADCHANGE
}

Public Member Functions

bool getCurrentResult (sensor_msgs::Image &image)
void getCurrentSegmFlags (bool &with_colors, bool &with_color_holes_, bool &uniform_, bool &with_disparities_, bool &with_surface_)
void getCurrentSurface (float &alpha, float &beta, float &gamma)
 ObjectSegmenter (float grad_weight, int n_iter, bool use_gpu, float w_size=0.20f, float b_size=0.20f)
void queueAction (const Action &action)
void setCurrentSegmFlags (bool with_colors, bool with_color_holes, bool uniform, bool with_disparities, bool with_surface)
void setNewData (const sensor_msgs::Image &image_, const stereo_msgs::DisparityImage &disparity_)
 ~ObjectSegmenter ()

Private Member Functions

void clearQueue ()
bool dequeueAction (Action &action)
void doSegment ()
void fillImage (sensor_msgs::Image &image, const Image< uint8_t > &segm_mask)
void fillInitMask (Image< uint8_t > &init_mask, int start_x, int start_y, int stop_x, int stop_y)
void pause ()
void setCurrentResult ()
template<typename Callable >
void startThread (Callable f)
void stopThread ()
bool validResult (const Image< uint8_t > &segm_mask)
void waitForAction ()

Private Attributes

std::deque< Actionaction_queue_
float alpha_
float ball_size_
float beta_
boost::condition_variable cond_var_
int drange_
FgBgSegment * fgbgsegment
float gamma_
Image< float > gpu_disparities
Image< uint8_t > gpu_image
int grad_weight_
int h_
boost::mutex image_mutex_
bool init_
Image< uint8_t > init_mask
int n_iter_
int num_fg_hypos_
boost::mutex queue_mutex_
Image< uint8_t > segm_mask
boost::thread * thread_
bool use_gpu_
int w_
float window_size_

Detailed Description

Definition at line 50 of file object_segmenter.h.


Member Enumeration Documentation

Enumerator:
PAUSE 
RESET 
CLICK 
REGION 
STOP 
GRADCHANGE 

Definition at line 54 of file object_segmenter.h.


Constructor & Destructor Documentation

object_segmentation_gui::ObjectSegmenter::ObjectSegmenter ( float  grad_weight,
int  n_iter,
bool  use_gpu,
float  w_size = 0.20f,
float  b_size = 0.20f 
)

Definition at line 35 of file object_segmenter.cpp.

object_segmentation_gui::ObjectSegmenter::~ObjectSegmenter (  ) 

Definition at line 55 of file object_segmenter.cpp.


Member Function Documentation

void object_segmentation_gui::ObjectSegmenter::clearQueue (  )  [private]

Definition at line 157 of file object_segmenter.cpp.

bool object_segmentation_gui::ObjectSegmenter::dequeueAction ( Action action  )  [private]

Definition at line 142 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::doSegment (  )  [private]

Definition at line 267 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::fillImage ( sensor_msgs::Image &  image,
const Image< uint8_t > &  segm_mask 
) [private]

Definition at line 368 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::fillInitMask ( Image< uint8_t > &  init_mask,
int  start_x,
int  start_y,
int  stop_x,
int  stop_y 
) [private]

Definition at line 346 of file object_segmenter.cpp.

bool object_segmentation_gui::ObjectSegmenter::getCurrentResult ( sensor_msgs::Image &  image  ) 

Definition at line 182 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::getCurrentSegmFlags ( bool &  with_colors,
bool &  with_color_holes_,
bool &  uniform_,
bool &  with_disparities_,
bool &  with_surface_ 
)

Definition at line 240 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::getCurrentSurface ( float &  alpha,
float &  beta,
float &  gamma 
)

Definition at line 231 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::pause (  )  [private]

Definition at line 172 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::queueAction ( const Action action  ) 

Definition at line 131 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::setCurrentResult (  )  [private]

Definition at line 192 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::setCurrentSegmFlags ( bool  with_colors,
bool  with_color_holes,
bool  uniform,
bool  with_disparities,
bool  with_surface 
)

Definition at line 253 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::setNewData ( const sensor_msgs::Image &  image_,
const stereo_msgs::DisparityImage &  disparity_ 
)

Definition at line 70 of file object_segmenter.cpp.

template<typename Callable >
void object_segmentation_gui::ObjectSegmenter::startThread ( Callable  f  )  [inline, private]

Definition at line 329 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::stopThread (  )  [private]

Definition at line 338 of file object_segmenter.cpp.

bool object_segmentation_gui::ObjectSegmenter::validResult ( const Image< uint8_t > &  segm_mask  )  [private]

Definition at line 199 of file object_segmenter.cpp.

void object_segmentation_gui::ObjectSegmenter::waitForAction (  )  [private]

Definition at line 163 of file object_segmenter.cpp.


Member Data Documentation

Definition at line 163 of file object_segmenter.h.

Definition at line 160 of file object_segmenter.h.

Definition at line 140 of file object_segmenter.h.

Definition at line 160 of file object_segmenter.h.

boost::condition_variable object_segmentation_gui::ObjectSegmenter::cond_var_ [private]

Definition at line 169 of file object_segmenter.h.

Definition at line 137 of file object_segmenter.h.

Definition at line 149 of file object_segmenter.h.

Definition at line 160 of file object_segmenter.h.

Definition at line 153 of file object_segmenter.h.

Definition at line 152 of file object_segmenter.h.

Definition at line 136 of file object_segmenter.h.

Definition at line 135 of file object_segmenter.h.

Definition at line 167 of file object_segmenter.h.

Definition at line 145 of file object_segmenter.h.

Definition at line 156 of file object_segmenter.h.

Definition at line 143 of file object_segmenter.h.

Definition at line 147 of file object_segmenter.h.

Definition at line 166 of file object_segmenter.h.

Definition at line 159 of file object_segmenter.h.

Definition at line 165 of file object_segmenter.h.

Definition at line 142 of file object_segmenter.h.

Definition at line 134 of file object_segmenter.h.

Definition at line 139 of file object_segmenter.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


object_segmentation_gui
Author(s): David Gossow
autogenerated on Fri Jan 11 10:03:23 2013