object_segmentation_gui::ObjectSegmentationRvizUI Class Reference

#include <object_segmentation_rviz_ui.h>

Inheritance diagram for object_segmentation_gui::ObjectSegmentationRvizUI:
Inheritance graph
[legend]

List of all members.

Classes

struct  ClickInfo

Public Member Functions

 ObjectSegmentationRvizUI (rviz::VisualizationManager *visualization_manager)
void startActionServer (ros::NodeHandle &node_handle)
void stopActionServer ()
virtual void update (float wall_dt, float ros_dt)
virtual ~ObjectSegmentationRvizUI ()

Protected Member Functions

virtual void acceptButtonClicked (wxCommandEvent &)
void acceptNewGoal ()
void addColorCode ()
virtual void cancelButtonClicked (wxCommandEvent &)
void cleanupAndHide ()
void createRenderPanel (rviz::VisualizationManager *visualization_manager)
void filterOutliersAndDownsample (std::vector< sensor_msgs::PointCloud > &clusters)
virtual void gradWeightChanged (wxScrollEvent &event)
virtual void onRenderWindowMouseEvents (wxMouseEvent &event)
void preempt ()
void reconstructAndClusterPointCloud (ObjectSegmentationGuiResult &result)
virtual void resetButtonClicked (wxCommandEvent &)
virtual void restartButtonClicked (wxCommandEvent &event)
virtual void segmentButtonClicked (wxCommandEvent &)
void stopSegmentation ()
virtual void uniformChecked (wxCommandEvent &event)
virtual void withColorChecked (wxCommandEvent &event)
virtual void withDisparityChecked (wxCommandEvent &event)
virtual void withHolesChecked (wxCommandEvent &event)
virtual void withSurfaceChecked (wxCommandEvent &event)

Protected Attributes

Ogre::ManualObject * box_object_
ClickInfo click_info_
rviz_interaction_tools::ImageOverlay * image_overlay_
actionlib::SimpleActionServer
< ObjectSegmentationGuiAction > * 
object_segmentation_server_
rviz::RenderPanel * render_panel_
Ogre::SceneManager * scene_manager_
Ogre::SceneNode * scene_root_
rviz::WindowManagerInterface * window_manager_

Private Types

typedef geometry_msgs::Point32 Point
enum  ResetType {
  PLAIN, COLOR, SURFACE, DISP,
  HOLES, UNIFORM
}

Private Member Functions

void addToMasks (const ObjectSegmenter::Box2D &select_)
void fillRgbImage (sensor_msgs::Image &rgb_img, const sensor_msgs::PointCloud2 &point_cloud)
void getClusterSize ()
void includeFlags (ObjectSegmenter::Action &ac)
void initStorage (const sensor_msgs::Image &image)
void overlaySegmentationMask ()
void reset ()
void resetVars ()
void segment ()
int sumLabels (const sensor_msgs::Image &image)
void updateSelectBox (int start_x, int start_y, int stop_x, int stop_y)

Private Attributes

double ball_size_
double clustering_voxel_size_
 voxel grid filtering parameters
std::vector
< sensor_msgs::PointCloud > 
clusters_
std::vector< int > color_code_
sensor_msgs::CameraInfo current_camera_info_
stereo_msgs::DisparityImage current_disparity_image_
sensor_msgs::Image current_image_
int current_marker_id_
 The current marker being published.
sensor_msgs::PointCloud2 current_point_cloud_
double grad_weight_
image_transport::Publisher image_pub_
 Publishing images (for debug only).
sensor_msgs::Image inits_
int inlier_threshold_
 parameters for table plane detection
sensor_msgs::Image labels_
ros::Publisher marker_pub_
 Publisher for markers.
double mean_k_
 statistical outlier removal parameters
int n_iter_
ros::NodeHandle nh_
 The node handle.
int num_fg_hypos_
int num_markers_published_
 Used to remember the number of markers we publish so we can delete them later.
ObjectSegmenterobject_segmenter_
bool paused_
std::deque
< ObjectSegmenter::Box2D
previous_queue_
ros::NodeHandle priv_nh_
 The node handle.
std::deque
< ObjectSegmenter::Box2D
region_queue_
bool running_
std::vector< int > segm_size_
double std_
sensor_msgs::PointCloud table_points_
TableTransform table_transformer_
sensor_msgs::Image texture_buffer_
double up_direction_
bool use_gpu_
double window_size_

Detailed Description

Definition at line 67 of file object_segmentation_rviz_ui.h.


Member Typedef Documentation

typedef geometry_msgs::Point32 object_segmentation_gui::ObjectSegmentationRvizUI::Point [private]

Definition at line 69 of file object_segmentation_rviz_ui.h.


Member Enumeration Documentation

Enumerator:
PLAIN 
COLOR 
SURFACE 
DISP 
HOLES 
UNIFORM 

Definition at line 147 of file object_segmentation_rviz_ui.h.


Constructor & Destructor Documentation

object_segmentation_gui::ObjectSegmentationRvizUI::ObjectSegmentationRvizUI ( rviz::VisualizationManager *  visualization_manager  ) 

Publisher for images (debugging only)

Definition at line 78 of file object_segmentation_rviz_ui.cpp.

object_segmentation_gui::ObjectSegmentationRvizUI::~ObjectSegmentationRvizUI (  )  [virtual]

Definition at line 157 of file object_segmentation_rviz_ui.cpp.


Member Function Documentation

void object_segmentation_gui::ObjectSegmentationRvizUI::acceptButtonClicked ( wxCommandEvent &   )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 755 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::acceptNewGoal (  )  [protected]

Definition at line 269 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::addColorCode (  )  [protected]

Definition at line 563 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::addToMasks ( const ObjectSegmenter::Box2D select_  )  [private]

Definition at line 575 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::cancelButtonClicked ( wxCommandEvent &   )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 805 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::cleanupAndHide (  )  [protected]

Definition at line 367 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::createRenderPanel ( rviz::VisualizationManager *  visualization_manager  )  [protected]

Definition at line 168 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::fillRgbImage ( sensor_msgs::Image &  rgb_img,
const sensor_msgs::PointCloud2 &  point_cloud 
) [private]

Definition at line 622 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::filterOutliersAndDownsample ( std::vector< sensor_msgs::PointCloud > &  clusters  )  [protected]

Definition at line 1082 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::getClusterSize (  )  [private]

Definition at line 985 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::gradWeightChanged ( wxScrollEvent &  event  )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 976 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::includeFlags ( ObjectSegmenter::Action ac  )  [private]

Definition at line 865 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::initStorage ( const sensor_msgs::Image &  image  )  [private]

Definition at line 337 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::onRenderWindowMouseEvents ( wxMouseEvent &  event  )  [protected, virtual]

Definition at line 465 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::overlaySegmentationMask (  )  [private]

Definition at line 657 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::preempt (  )  [protected]

Definition at line 360 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::reconstructAndClusterPointCloud ( ObjectSegmentationGuiResult result  )  [protected]

Definition at line 1013 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::reset (  )  [private]

Definition at line 818 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::resetButtonClicked ( wxCommandEvent &   )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 812 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::resetVars (  )  [private]

Definition at line 384 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::restartButtonClicked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 832 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::segment (  )  [private]

Definition at line 894 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::segmentButtonClicked ( wxCommandEvent &   )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 876 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::startActionServer ( ros::NodeHandle &  node_handle  ) 

Definition at line 225 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::stopActionServer (  ) 

Definition at line 247 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::stopSegmentation (  )  [protected]

Definition at line 377 of file object_segmentation_rviz_ui.cpp.

int object_segmentation_gui::ObjectSegmentationRvizUI::sumLabels ( const sensor_msgs::Image &  image  )  [private]

Definition at line 452 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::uniformChecked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 973 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::update ( float  wall_dt,
float  ros_dt 
) [virtual]

Definition at line 422 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::updateSelectBox ( int  start_x,
int  start_y,
int  stop_x,
int  stop_y 
) [private]

Definition at line 724 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::withColorChecked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 954 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::withDisparityChecked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 943 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::withHolesChecked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 970 of file object_segmentation_rviz_ui.cpp.

void object_segmentation_gui::ObjectSegmentationRvizUI::withSurfaceChecked ( wxCommandEvent &  event  )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 940 of file object_segmentation_rviz_ui.cpp.


Member Data Documentation

Definition at line 187 of file object_segmentation_rviz_ui.h.

Definition at line 141 of file object_segmentation_rviz_ui.h.

Definition at line 140 of file object_segmentation_rviz_ui.h.

voxel grid filtering parameters

Definition at line 255 of file object_segmentation_rviz_ui.h.

std::vector<sensor_msgs::PointCloud> object_segmentation_gui::ObjectSegmentationRvizUI::clusters_ [private]

Point clusters

Definition at line 234 of file object_segmentation_rviz_ui.h.

Definition at line 225 of file object_segmentation_rviz_ui.h.

Definition at line 210 of file object_segmentation_rviz_ui.h.

Definition at line 208 of file object_segmentation_rviz_ui.h.

Definition at line 207 of file object_segmentation_rviz_ui.h.

The current marker being published.

Definition at line 244 of file object_segmentation_rviz_ui.h.

Definition at line 209 of file object_segmentation_rviz_ui.h.

Definition at line 185 of file object_segmentation_rviz_ui.h.

rviz_interaction_tools::ImageOverlay* object_segmentation_gui::ObjectSegmentationRvizUI::image_overlay_ [protected]

Definition at line 124 of file object_segmentation_rviz_ui.h.

Publishing images (for debug only).

Definition at line 156 of file object_segmentation_rviz_ui.h.

Definition at line 216 of file object_segmentation_rviz_ui.h.

parameters for table plane detection

Definition at line 247 of file object_segmentation_rviz_ui.h.

Definition at line 213 of file object_segmentation_rviz_ui.h.

Publisher for markers.

Definition at line 240 of file object_segmentation_rviz_ui.h.

statistical outlier removal parameters

Definition at line 251 of file object_segmentation_rviz_ui.h.

Definition at line 188 of file object_segmentation_rviz_ui.h.

The node handle.

Definition at line 150 of file object_segmentation_rviz_ui.h.

Definition at line 195 of file object_segmentation_rviz_ui.h.

Used to remember the number of markers we publish so we can delete them later.

Definition at line 242 of file object_segmentation_rviz_ui.h.

Definition at line 143 of file object_segmentation_rviz_ui.h.

Definition at line 192 of file object_segmentation_rviz_ui.h.

Definition at line 222 of file object_segmentation_rviz_ui.h.

Definition at line 201 of file object_segmentation_rviz_ui.h.

The node handle.

Definition at line 153 of file object_segmentation_rviz_ui.h.

Definition at line 198 of file object_segmentation_rviz_ui.h.

Definition at line 119 of file object_segmentation_rviz_ui.h.

Definition at line 221 of file object_segmentation_rviz_ui.h.

Definition at line 121 of file object_segmentation_rviz_ui.h.

Definition at line 122 of file object_segmentation_rviz_ui.h.

Number of points in each segment Number of pixels might be bigger since parts of the image without disparity information can be included in the segment.

Definition at line 231 of file object_segmentation_rviz_ui.h.

Definition at line 252 of file object_segmentation_rviz_ui.h.

Point belonging to table plane

Definition at line 237 of file object_segmentation_rviz_ui.h.

Definition at line 204 of file object_segmentation_rviz_ui.h.

Definition at line 219 of file object_segmentation_rviz_ui.h.

Definition at line 248 of file object_segmentation_rviz_ui.h.

Definition at line 189 of file object_segmentation_rviz_ui.h.

rviz::WindowManagerInterface* object_segmentation_gui::ObjectSegmentationRvizUI::window_manager_ [protected]

Definition at line 118 of file object_segmentation_rviz_ui.h.

Definition at line 186 of file object_segmentation_rviz_ui.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