$search
#include <object_segmentation_ui.h>
Definition at line 77 of file object_segmentation_ui.h.
typedef geometry_msgs::Point32 image_segmentation_demo::ObjectSegmentationUI::Point [private] |
Definition at line 77 of file object_segmentation_ui_old.h.
enum image_segmentation_demo::ObjectSegmentationUI::ResetType [private] |
Definition at line 132 of file object_segmentation_ui_old.h.
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] |
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.
std::string image_segmentation_demo::ObjectSegmentationUI::ARM_ACTION_NAME [private] |
Definition at line 107 of file object_segmentation_ui.h.
cv::Mat image_segmentation_demo::ObjectSegmentationUI::binary_mask_ [private] |
Definition at line 148 of file object_segmentation_ui.h.
Ogre::Camera* image_segmentation_demo::ObjectSegmentationUI::camera_ [private] |
Definition at line 95 of file object_segmentation_ui.h.
Definition at line 99 of file object_segmentation_ui.h.
std::vector< sensor_msgs::PointCloud > image_segmentation_demo::ObjectSegmentationUI::clusters_ [private] |
Point clusters
Definition at line 152 of file object_segmentation_ui.h.
std::string image_segmentation_demo::ObjectSegmentationUI::COLLISION_PROCESSING_SERVICE_NAME [private] |
Definition at line 103 of file object_segmentation_ui.h.
ros::ServiceClient image_segmentation_demo::ObjectSegmentationUI::collision_processing_srv [private] |
Definition at line 119 of file object_segmentation_ui.h.
sensor_msgs::CameraInfo image_segmentation_demo::ObjectSegmentationUI::current_camera_info_ [private] |
Definition at line 126 of file object_segmentation_ui.h.
Definition at line 124 of file object_segmentation_ui.h.
stereo_msgs::DisparityImage image_segmentation_demo::ObjectSegmentationUI::current_disparity_image_ [private] |
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.
sensor_msgs::PointCloud2 image_segmentation_demo::ObjectSegmentationUI::current_point_cloud_ [private] |
Definition at line 127 of file object_segmentation_ui.h.
std::string image_segmentation_demo::ObjectSegmentationUI::data_location_ [private] |
Definition at line 109 of file object_segmentation_ui.h.
std::string image_segmentation_demo::ObjectSegmentationUI::data_string_ [private] |
Definition at line 113 of file object_segmentation_ui.h.
tabletop_object_detector::TabletopDetectionResult image_segmentation_demo::ObjectSegmentationUI::detection_call_ [private] |
Definition at line 136 of file object_segmentation_ui.h.
Definition at line 123 of file object_segmentation_ui.h.
rviz_interaction_tools::ImageOverlay* image_segmentation_demo::ObjectSegmentationUI::image_overlay_ [protected] |
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.
ros::NodeHandlePtr image_segmentation_demo::ObjectSegmentationUI::nh [private] |
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.
std::string image_segmentation_demo::ObjectSegmentationUI::OBJECT_DETECTION_SERVICE_NAME [private] |
Definition at line 102 of file object_segmentation_ui.h.
Definition at line 118 of file object_segmentation_ui.h.
bool image_segmentation_demo::ObjectSegmentationUI::object_grasp_ [private] |
Definition at line 115 of file object_segmentation_ui.h.
GrabCut3DObjectSegmenter * image_segmentation_demo::ObjectSegmentationUI::object_segmenter_ [private] |
Definition at line 130 of file object_segmentation_ui.h.
std::string image_segmentation_demo::ObjectSegmentationUI::PICKUP_ACTION_NAME [private] |
Definition at line 104 of file object_segmentation_ui.h.
actionlib::SimpleActionClient<object_manipulation_msgs::PickupAction>* image_segmentation_demo::ObjectSegmentationUI::pickup_client [private] |
Definition at line 143 of file object_segmentation_ui.h.
std::string image_segmentation_demo::ObjectSegmentationUI::PLACE_ACTION_NAME [private] |
Definition at line 105 of file object_segmentation_ui.h.
actionlib::SimpleActionClient<object_manipulation_msgs::PlaceAction>* image_segmentation_demo::ObjectSegmentationUI::place_client [private] |
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.
ogre_tools::wxOgreRenderWindow* image_segmentation_demo::ObjectSegmentationUI::render_window_ [private] |
Definition at line 94 of file object_segmentation_ui.h.
Definition at line 117 of file object_segmentation_ui.h.
rgbd_assembler::RgbdAssembly image_segmentation_demo::ObjectSegmentationUI::rgbd_assembler_srv_ [private] |
Definition at line 139 of file object_segmentation_ui.h.
std::string image_segmentation_demo::ObjectSegmentationUI::RGBD_ASSEMBLY_SERVICE_NAME [private] |
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.
Ogre::Root* image_segmentation_demo::ObjectSegmentationUI::root_ [private] |
Definition at line 92 of file object_segmentation_ui.h.
Ogre::SceneManager * image_segmentation_demo::ObjectSegmentationUI::scene_manager_ [private] |
Definition at line 93 of file object_segmentation_ui.h.
Ogre::SceneNode* image_segmentation_demo::ObjectSegmentationUI::scene_root_ [protected] |
Definition at line 121 of file object_segmentation_ui_old.h.
time_t image_segmentation_demo::ObjectSegmentationUI::start_time_ [private] |
Definition at line 111 of file object_segmentation_ui.h.
time_t image_segmentation_demo::ObjectSegmentationUI::stop_time_ [private] |
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.
rviz::WindowManagerInterface* image_segmentation_demo::ObjectSegmentationUI::window_manager_ [protected] |
Definition at line 117 of file object_segmentation_ui_old.h.