$search

image_segmentation_demo::ObjectSegmentationUI Class Reference

#include <object_segmentation_ui.h>

Inheritance diagram for image_segmentation_demo::ObjectSegmentationUI:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void acceptButtonClicked (wxCommandEvent &)
virtual void cancelButtonClicked (wxCommandEvent &)
void cleanupAndQuit ()
 ObjectSegmentationUI ()
 ObjectSegmentationUI (wxWindow *parentwindow)
virtual void onRenderWindowMouseEvents (wxMouseEvent &event)
virtual void refreshButtonClicked (wxCommandEvent &)
virtual void resetButtonClicked (wxCommandEvent &)
virtual void segmentButtonClicked (wxCommandEvent &)
virtual void update (float wall_dt, float ros_dt)
virtual void update (float wall_dt, float ros_dt)
virtual ~ObjectSegmentationUI ()
virtual ~ObjectSegmentationUI ()

Protected Member Functions

virtual void acceptButtonClicked (wxCommandEvent &)
virtual void cancelButtonClicked (wxCommandEvent &)
void cleanupAndHide ()
void createRenderPanel ()
virtual void onRenderWindowMouseEvents (wxMouseEvent &event)
void reconstructAndClusterPointCloud (tabletop_object_detector::TabletopDetection &result)
virtual void resetButtonClicked (wxCommandEvent &)
virtual void segmentButtonClicked (wxCommandEvent &)
void stopSegmentation ()

Protected Attributes

rviz_interaction_tools::ImageOverlayimage_overlay_
rviz::RenderPanelrender_panel_
Ogre::SceneNode * scene_root_
rviz::WindowManagerInterfacewindow_manager_

Private Types

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

Private Member Functions

bool convertImageMessageToMat (const sensor_msgs::Image &image_msg, Mat &image)
bool convertImageMessageToMat (const sensor_msgs::Image &image_msg, Mat &image)
bool convertMatToImageMessage (const Mat &image, sensor_msgs::Image &image_msg)
bool convertMatToImageMessage (const Mat &image, sensor_msgs::Image &image_msg)
void fillRgbImage (sensor_msgs::Image &rgb_img, const sensor_msgs::PointCloud2 &point_cloud)
void fillRgbImage (sensor_msgs::Image &rgb_img, const sensor_msgs::PointCloud2 &point_cloud)
bool getDepthImage (sensor_msgs::Image &image_msg)
bool getDepthImage (sensor_msgs::Image &image_msg)
bool GetSensorData ()
void overlaySegmentationMask ()
void reconstructAndClusterPointCloud ()
void resetVars ()
void resetVars ()
void RunRestOfPickAndPlace ()
void saveData ()
void setUpEventHandlers ()
void SetUpPickandPlaceApp ()
bool transformPointCloud (const std::string &target_frame, const sensor_msgs::PointCloud2 &cloud_in, sensor_msgs::PointCloud2 &cloud_out)
void update ()
void updateImageOverlay ()
void updateImageOverlay ()
void updateView ()

Private Attributes

std::string ARM_ACTION_NAME
cv::Mat binary_mask_
Ogre::Camera * camera_
ros::Publisher chatter_pub
std::vector
< sensor_msgs::PointCloud
clusters_
std::string COLLISION_PROCESSING_SERVICE_NAME
ros::ServiceClient collision_processing_srv
sensor_msgs::CameraInfo current_camera_info_
sensor_msgs::Image current_depth_image_
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_
std::string data_location_
std::string data_string_
tabletop_object_detector::TabletopDetectionResult detection_call_
sensor_msgs::Image display_image_
image_transport::Publisher image_pub_
 Publishing images (for debug only).
tf::TransformListener listener_
 A tf transform listener.
ros::Publisher marker_pub_
 Publisher for markers.
ros::NodeHandlePtr nh
 The node handle.
ros::NodeHandle nh_
 The node handle.
int num_markers_published_
 Used to remember the number of markers we publish so we can delete them later.
int num_resets_
std::string OBJECT_DETECTION_SERVICE_NAME
ros::ServiceClient object_detection_srv
bool object_grasp_
GrabCut3DObjectSegmenterobject_segmenter_
std::string PICKUP_ACTION_NAME
actionlib::SimpleActionClient
< object_manipulation_msgs::PickupAction > * 
pickup_client
std::string PLACE_ACTION_NAME
actionlib::SimpleActionClient
< object_manipulation_msgs::PlaceAction > * 
place_client
ros::NodeHandle priv_nh_
 The node handle.
bool recording_time_
ogre_tools::wxOgreRenderWindowrender_window_
ros::ServiceClient rgbd_assembler_client_
rgbd_assembler::RgbdAssembly rgbd_assembler_srv_
std::string RGBD_ASSEMBLY_SERVICE_NAME
simple_robot_control::Robot robot_
Ogre::Root * root_
Ogre::SceneManager * scene_manager_
time_t start_time_
time_t stop_time_
TableDetector table_detector_
ROSImageTexturetexture_

Detailed Description

Definition at line 77 of file object_segmentation_ui.h.


Member Typedef Documentation

Definition at line 77 of file object_segmentation_ui_old.h.


Member Enumeration Documentation

Enumerator:
PLAIN 
COLOR 
SURFACE 
DISP 
HOLES 
UNIFORM 

Definition at line 132 of file object_segmentation_ui_old.h.


Constructor & Destructor Documentation

image_segmentation_demo::ObjectSegmentationUI::ObjectSegmentationUI ( wxWindow *  parentwindow  ) 

Constructor for ObjectSegmentationUI class

Definition at line 70 of file object_segmentation_ui.cpp.

image_segmentation_demo::ObjectSegmentationUI::~ObjectSegmentationUI (  )  [virtual]

Definition at line 152 of file object_segmentation_ui.cpp.

image_segmentation_demo::ObjectSegmentationUI::ObjectSegmentationUI (  ) 
virtual image_segmentation_demo::ObjectSegmentationUI::~ObjectSegmentationUI (  )  [virtual]

Member Function Documentation

virtual void image_segmentation_demo::ObjectSegmentationUI::acceptButtonClicked ( wxCommandEvent &   )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

void image_segmentation_demo::ObjectSegmentationUI::acceptButtonClicked ( wxCommandEvent &   )  [virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 181 of file object_segmentation_ui.cpp.

virtual void image_segmentation_demo::ObjectSegmentationUI::cancelButtonClicked ( wxCommandEvent &   )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

void image_segmentation_demo::ObjectSegmentationUI::cancelButtonClicked ( wxCommandEvent &   )  [virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 208 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::cleanupAndHide (  )  [protected]
void image_segmentation_demo::ObjectSegmentationUI::cleanupAndQuit (  ) 

Definition at line 323 of file object_segmentation_ui.cpp.

bool image_segmentation_demo::ObjectSegmentationUI::convertImageMessageToMat ( const sensor_msgs::Image image_msg,
Mat &  image 
) [private]
bool image_segmentation_demo::ObjectSegmentationUI::convertImageMessageToMat ( const sensor_msgs::Image image_msg,
Mat &  image 
) [private]

Definition at line 526 of file object_segmentation_ui.cpp.

bool image_segmentation_demo::ObjectSegmentationUI::convertMatToImageMessage ( const Mat &  image,
sensor_msgs::Image image_msg 
) [private]
bool image_segmentation_demo::ObjectSegmentationUI::convertMatToImageMessage ( const Mat &  image,
sensor_msgs::Image image_msg 
) [private]

Definition at line 550 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::createRenderPanel (  )  [protected]
void image_segmentation_demo::ObjectSegmentationUI::fillRgbImage ( sensor_msgs::Image rgb_img,
const sensor_msgs::PointCloud2 point_cloud 
) [private]
void image_segmentation_demo::ObjectSegmentationUI::fillRgbImage ( sensor_msgs::Image rgb_img,
const sensor_msgs::PointCloud2 point_cloud 
) [private]

Definition at line 430 of file object_segmentation_ui.cpp.

bool image_segmentation_demo::ObjectSegmentationUI::getDepthImage ( sensor_msgs::Image image_msg  )  [private]
bool image_segmentation_demo::ObjectSegmentationUI::getDepthImage ( sensor_msgs::Image image_msg  )  [private]

Definition at line 469 of file object_segmentation_ui.cpp.

bool image_segmentation_demo::ObjectSegmentationUI::GetSensorData (  )  [private]

Definition at line 361 of file object_segmentation_ui.cpp.

virtual void image_segmentation_demo::ObjectSegmentationUI::onRenderWindowMouseEvents ( wxMouseEvent &  event  )  [protected, virtual]
void image_segmentation_demo::ObjectSegmentationUI::onRenderWindowMouseEvents ( wxMouseEvent &  event  )  [virtual]

Definition at line 262 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::overlaySegmentationMask (  )  [private]
void image_segmentation_demo::ObjectSegmentationUI::reconstructAndClusterPointCloud ( tabletop_object_detector::TabletopDetection result  )  [protected]
void image_segmentation_demo::ObjectSegmentationUI::reconstructAndClusterPointCloud (  )  [private]

Definition at line 573 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::refreshButtonClicked ( wxCommandEvent &   )  [virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 216 of file object_segmentation_ui.cpp.

virtual void image_segmentation_demo::ObjectSegmentationUI::resetButtonClicked ( wxCommandEvent &   )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

void image_segmentation_demo::ObjectSegmentationUI::resetButtonClicked ( wxCommandEvent &   )  [virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 227 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::resetVars (  )  [private]
void image_segmentation_demo::ObjectSegmentationUI::resetVars (  )  [private]

Definition at line 622 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::RunRestOfPickAndPlace (  )  [private]

Definition at line 750 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::saveData (  )  [private]

Definition at line 647 of file object_segmentation_ui.cpp.

virtual void image_segmentation_demo::ObjectSegmentationUI::segmentButtonClicked ( wxCommandEvent &   )  [protected, virtual]

Reimplemented from ObjectSegmentationFrame.

void image_segmentation_demo::ObjectSegmentationUI::segmentButtonClicked ( wxCommandEvent &   )  [virtual]

Reimplemented from ObjectSegmentationFrame.

Definition at line 239 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::setUpEventHandlers (  )  [private]

Definition at line 161 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::SetUpPickandPlaceApp (  )  [private]

Initializes the manipulation pipeline

Definition at line 700 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::stopSegmentation (  )  [protected]
bool image_segmentation_demo::ObjectSegmentationUI::transformPointCloud ( const std::string &  target_frame,
const sensor_msgs::PointCloud2 cloud_in,
sensor_msgs::PointCloud2 cloud_out 
) [private]

Definition at line 400 of file object_segmentation_ui.cpp.

virtual void image_segmentation_demo::ObjectSegmentationUI::update ( float  wall_dt,
float  ros_dt 
) [virtual]
void image_segmentation_demo::ObjectSegmentationUI::update (  )  [private]
void image_segmentation_demo::ObjectSegmentationUI::update ( float  wall_dt,
float  ros_dt 
) [virtual]

Definition at line 347 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::updateImageOverlay (  )  [private]
void image_segmentation_demo::ObjectSegmentationUI::updateImageOverlay (  )  [private]

Definition at line 350 of file object_segmentation_ui.cpp.

void image_segmentation_demo::ObjectSegmentationUI::updateView (  )  [private]

Definition at line 332 of file object_segmentation_ui.cpp.


Member Data Documentation

Definition at line 107 of file object_segmentation_ui.h.

Definition at line 148 of file object_segmentation_ui.h.

Definition at line 95 of file object_segmentation_ui.h.

Definition at line 99 of file object_segmentation_ui.h.

Point clusters

Definition at line 152 of file object_segmentation_ui.h.

Definition at line 103 of file object_segmentation_ui.h.

Definition at line 119 of file object_segmentation_ui.h.

Definition at line 126 of file object_segmentation_ui.h.

Definition at line 124 of file object_segmentation_ui.h.

Definition at line 125 of file object_segmentation_ui.h.

Definition at line 122 of file object_segmentation_ui.h.

The current marker being published.

Definition at line 159 of file object_segmentation_ui.h.

Definition at line 127 of file object_segmentation_ui.h.

Definition at line 109 of file object_segmentation_ui.h.

Definition at line 113 of file object_segmentation_ui.h.

Definition at line 136 of file object_segmentation_ui.h.

Definition at line 123 of file object_segmentation_ui.h.

Definition at line 123 of file object_segmentation_ui_old.h.

Publishing images (for debug only).

Definition at line 141 of file object_segmentation_ui_old.h.

A tf transform listener.

Definition at line 133 of file object_segmentation_ui.h.

Publisher for markers.

Definition at line 155 of file object_segmentation_ui.h.

The node handle.

Definition at line 98 of file object_segmentation_ui.h.

The node handle.

Definition at line 135 of file object_segmentation_ui_old.h.

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

Definition at line 157 of file object_segmentation_ui.h.

Definition at line 114 of file object_segmentation_ui.h.

Definition at line 102 of file object_segmentation_ui.h.

Definition at line 118 of file object_segmentation_ui.h.

Definition at line 115 of file object_segmentation_ui.h.

Definition at line 130 of file object_segmentation_ui.h.

Definition at line 104 of file object_segmentation_ui.h.

Definition at line 143 of file object_segmentation_ui.h.

Definition at line 105 of file object_segmentation_ui.h.

Definition at line 144 of file object_segmentation_ui.h.

The node handle.

Definition at line 138 of file object_segmentation_ui_old.h.

Definition at line 110 of file object_segmentation_ui.h.

Definition at line 118 of file object_segmentation_ui_old.h.

Definition at line 94 of file object_segmentation_ui.h.

Definition at line 117 of file object_segmentation_ui.h.

Definition at line 139 of file object_segmentation_ui.h.

Definition at line 106 of file object_segmentation_ui.h.

simple_robot_control::Robot image_segmentation_demo::ObjectSegmentationUI::robot_ [private]

Definition at line 141 of file object_segmentation_ui.h.

Definition at line 92 of file object_segmentation_ui.h.

Definition at line 93 of file object_segmentation_ui.h.

Definition at line 121 of file object_segmentation_ui_old.h.

Definition at line 111 of file object_segmentation_ui.h.

Definition at line 112 of file object_segmentation_ui.h.

Definition at line 135 of file object_segmentation_ui.h.

Definition at line 137 of file object_segmentation_ui.h.

Definition at line 117 of file object_segmentation_ui_old.h.


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


image_segmentation_demo
Author(s): Sarah Osentoski
autogenerated on Tue Mar 5 12:48:30 2013