$search
#include <object_segmentation_rviz_ui.h>
Definition at line 73 of file object_segmentation_rviz_ui.h.
typedef geometry_msgs::Point32 bosch_object_segmentation_gui::ObjectSegmentationRvizUI::Point [private] |
Definition at line 75 of file object_segmentation_rviz_ui.h.
Definition at line 128 of file object_segmentation_rviz_ui.h.
bosch_object_segmentation_gui::ObjectSegmentationRvizUI::ObjectSegmentationRvizUI | ( | rviz::VisualizationManager * | visualization_manager | ) |
Definition at line 88 of file object_segmentation_rviz_ui.cpp.
bosch_object_segmentation_gui::ObjectSegmentationRvizUI::~ObjectSegmentationRvizUI | ( | ) | [virtual] |
Definition at line 126 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::acceptButtonClicked | ( | wxCommandEvent & | ) | [protected, virtual] |
Reimplemented from ObjectSegmentationFrame.
Definition at line 459 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::acceptNewGoal | ( | ) | [protected] |
Definition at line 255 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::cancelButtonClicked | ( | wxCommandEvent & | ) | [protected, virtual] |
Reimplemented from ObjectSegmentationFrame.
Definition at line 483 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::cleanupAndHide | ( | ) | [protected] |
Definition at line 341 of file object_segmentation_rviz_ui.cpp.
bool bosch_object_segmentation_gui::ObjectSegmentationRvizUI::convertImageMessageToMat | ( | const sensor_msgs::Image & | image_msg, | |
Mat & | image | |||
) | [private] |
Definition at line 296 of file object_segmentation_rviz_ui.cpp.
bool bosch_object_segmentation_gui::ObjectSegmentationRvizUI::convertMatToImageMessage | ( | const Mat & | image, | |
sensor_msgs::Image & | image_msg | |||
) | [private] |
Definition at line 315 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::createRenderPanel | ( | rviz::VisualizationManager * | visualization_manager | ) | [protected] |
Definition at line 137 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::fillRgbImage | ( | sensor_msgs::Image & | rgb_img, | |
const sensor_msgs::PointCloud2 & | point_cloud | |||
) | [private] |
Definition at line 424 of file object_segmentation_rviz_ui.cpp.
bool bosch_object_segmentation_gui::ObjectSegmentationRvizUI::getDepthImage | ( | sensor_msgs::Image & | image_msg | ) | [private] |
Definition at line 208 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::onRenderWindowMouseEvents | ( | wxMouseEvent & | event | ) | [protected, virtual] |
Definition at line 374 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::overlaySegmentationMask | ( | ) | [private] |
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::preempt | ( | ) | [protected] |
Definition at line 334 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::reconstructAndClusterPointCloud | ( | ObjectSegmentationGuiResult & | result | ) | [protected] |
Definition at line 513 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::resetButtonClicked | ( | wxCommandEvent & | ) | [protected, virtual] |
Reimplemented from ObjectSegmentationFrame.
Definition at line 490 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::resetVars | ( | ) | [private] |
Definition at line 352 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::segmentButtonClicked | ( | wxCommandEvent & | ) | [protected, virtual] |
Reimplemented from ObjectSegmentationFrame.
Definition at line 498 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::startActionServer | ( | ros::NodeHandle & | node_handle | ) |
Definition at line 167 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::stopActionServer | ( | ) |
Definition at line 186 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::stopSegmentation | ( | ) | [protected] |
Definition at line 348 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::update | ( | float | wall_dt, | |
float | ros_dt | |||
) | [virtual] |
Definition at line 369 of file object_segmentation_rviz_ui.cpp.
void bosch_object_segmentation_gui::ObjectSegmentationRvizUI::updateImageOverlay | ( | ) | [private] |
Definition at line 416 of file object_segmentation_rviz_ui.cpp.
cv::Mat bosch_object_segmentation_gui::ObjectSegmentationRvizUI::binary_mask_ [private] |
Definition at line 172 of file object_segmentation_rviz_ui.h.
std::vector<sensor_msgs::PointCloud> bosch_object_segmentation_gui::ObjectSegmentationRvizUI::clusters_ [private] |
Point clusters
Definition at line 175 of file object_segmentation_rviz_ui.h.
sensor_msgs::CameraInfo bosch_object_segmentation_gui::ObjectSegmentationRvizUI::current_camera_info_ [private] |
Definition at line 169 of file object_segmentation_rviz_ui.h.
sensor_msgs::Image bosch_object_segmentation_gui::ObjectSegmentationRvizUI::current_depth_image_ [private] |
Definition at line 166 of file object_segmentation_rviz_ui.h.
stereo_msgs::DisparityImage bosch_object_segmentation_gui::ObjectSegmentationRvizUI::current_disparity_image_ [private] |
Definition at line 167 of file object_segmentation_rviz_ui.h.
sensor_msgs::Image bosch_object_segmentation_gui::ObjectSegmentationRvizUI::current_image_ [private] |
Definition at line 165 of file object_segmentation_rviz_ui.h.
The current marker being published.
Definition at line 182 of file object_segmentation_rviz_ui.h.
sensor_msgs::PointCloud2 bosch_object_segmentation_gui::ObjectSegmentationRvizUI::current_point_cloud_ [private] |
Definition at line 168 of file object_segmentation_rviz_ui.h.
rviz_interaction_tools::ImageOverlay* bosch_object_segmentation_gui::ObjectSegmentationRvizUI::image_overlay_ [protected] |
Definition at line 120 of file object_segmentation_rviz_ui.h.
image_transport::Publisher bosch_object_segmentation_gui::ObjectSegmentationRvizUI::image_pub_ [private] |
Publishing images (for debug only).
Definition at line 137 of file object_segmentation_rviz_ui.h.
Publisher for markers.
Definition at line 178 of file object_segmentation_rviz_ui.h.
The node handle.
Definition at line 131 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 180 of file object_segmentation_rviz_ui.h.
actionlib::SimpleActionServer<ObjectSegmentationGuiAction>* bosch_object_segmentation_gui::ObjectSegmentationRvizUI::object_segmentation_server_ [protected] |
Definition at line 124 of file object_segmentation_rviz_ui.h.
GrabCut3DObjectSegmenter* bosch_object_segmentation_gui::ObjectSegmentationRvizUI::object_segmenter_ [private] |
Definition at line 159 of file object_segmentation_rviz_ui.h.
The node handle.
Definition at line 134 of file object_segmentation_rviz_ui.h.
rviz::RenderPanel* bosch_object_segmentation_gui::ObjectSegmentationRvizUI::render_panel_ [protected] |
Definition at line 115 of file object_segmentation_rviz_ui.h.
Ogre::SceneManager* bosch_object_segmentation_gui::ObjectSegmentationRvizUI::scene_manager_ [protected] |
Definition at line 117 of file object_segmentation_rviz_ui.h.
Ogre::SceneNode* bosch_object_segmentation_gui::ObjectSegmentationRvizUI::scene_root_ [protected] |
Definition at line 118 of file object_segmentation_rviz_ui.h.
Definition at line 162 of file object_segmentation_rviz_ui.h.
rviz::WindowManagerInterface* bosch_object_segmentation_gui::ObjectSegmentationRvizUI::window_manager_ [protected] |
Definition at line 114 of file object_segmentation_rviz_ui.h.