#include <object_segmentation_rviz_ui.h>
Classes | |
struct | ClickInfo |
Public Member Functions | |
ObjectSegmentationRvizUI (rviz::VisualizationManager *visualization_manager, QWidget *parent=0) | |
void | startActionServer (ros::NodeHandle &node_handle) |
void | stopActionServer () |
virtual void | update (float wall_dt, float ros_dt) |
virtual | ~ObjectSegmentationRvizUI () |
Protected Slots | |
virtual void | acceptButtonClicked () |
virtual void | cancelButtonClicked () |
virtual void | gradWeightChanged (int new_value) |
virtual void | resetButtonClicked () |
virtual void | restartButtonClicked () |
virtual void | segmentButtonClicked () |
virtual void | uniformChecked () |
virtual void | withColorChecked () |
virtual void | withDisparityChecked () |
virtual void | withHolesChecked () |
virtual void | withSurfaceChecked () |
Protected Member Functions | |
void | acceptNewGoal () |
void | addColorCode () |
void | cleanupAndHide () |
virtual bool | eventFilter (QObject *watched_object, QEvent *event) |
void | filterOutliersAndDownsample (std::vector< sensor_msgs::PointCloud > &clusters) |
void | preempt () |
void | reconstructAndClusterPointCloud (ObjectSegmentationGuiResult &result) |
void | setupRenderPanel (rviz::VisualizationManager *visualization_manager) |
void | stopSegmentation () |
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. | |
ObjectSegmenter * | object_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_ |
Ui::MainFrame * | ui_ |
double | up_direction_ |
bool | use_gpu_ |
double | window_size_ |
Definition at line 69 of file object_segmentation_rviz_ui.h.
typedef geometry_msgs::Point32 object_segmentation_gui::ObjectSegmentationRvizUI::Point [private] |
Definition at line 72 of file object_segmentation_rviz_ui.h.
enum object_segmentation_gui::ObjectSegmentationRvizUI::ResetType [private] |
Definition at line 151 of file object_segmentation_rviz_ui.h.
object_segmentation_gui::ObjectSegmentationRvizUI::ObjectSegmentationRvizUI | ( | rviz::VisualizationManager * | visualization_manager, |
QWidget * | parent = 0 |
||
) |
Publisher for images (debugging only)
Definition at line 82 of file object_segmentation_rviz_ui.cpp.
Definition at line 188 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::acceptButtonClicked | ( | ) | [protected, virtual, slot] |
Definition at line 766 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::acceptNewGoal | ( | ) | [protected] |
Definition at line 255 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::addColorCode | ( | ) | [protected] |
Definition at line 574 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::addToMasks | ( | const ObjectSegmenter::Box2D & | select_ | ) | [private] |
Definition at line 586 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::cancelButtonClicked | ( | ) | [protected, virtual, slot] |
Definition at line 816 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::cleanupAndHide | ( | ) | [protected] |
Definition at line 353 of file object_segmentation_rviz_ui.cpp.
bool object_segmentation_gui::ObjectSegmentationRvizUI::eventFilter | ( | QObject * | watched_object, |
QEvent * | event | ||
) | [protected, virtual] |
Reimplemented from QObject to filter mouse events from render_panel_.
Definition at line 451 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 633 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::filterOutliersAndDownsample | ( | std::vector< sensor_msgs::PointCloud > & | clusters | ) | [protected] |
Definition at line 1093 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::getClusterSize | ( | ) | [private] |
Definition at line 996 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::gradWeightChanged | ( | int | new_value | ) | [protected, virtual, slot] |
Definition at line 987 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::includeFlags | ( | ObjectSegmenter::Action & | ac | ) | [private] |
Definition at line 876 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::initStorage | ( | const sensor_msgs::Image & | image | ) | [private] |
Definition at line 323 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::overlaySegmentationMask | ( | ) | [private] |
Definition at line 668 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::preempt | ( | ) | [protected] |
Definition at line 346 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::reconstructAndClusterPointCloud | ( | ObjectSegmentationGuiResult & | result | ) | [protected] |
Definition at line 1024 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::reset | ( | ) | [private] |
Definition at line 829 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::resetButtonClicked | ( | ) | [protected, virtual, slot] |
Definition at line 823 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::resetVars | ( | ) | [private] |
Definition at line 370 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::restartButtonClicked | ( | ) | [protected, virtual, slot] |
Definition at line 843 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::segment | ( | ) | [private] |
Definition at line 905 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::segmentButtonClicked | ( | ) | [protected, virtual, slot] |
Definition at line 887 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::setupRenderPanel | ( | rviz::VisualizationManager * | visualization_manager | ) | [protected] |
Definition at line 199 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::startActionServer | ( | ros::NodeHandle & | node_handle | ) |
Definition at line 211 of file object_segmentation_rviz_ui.cpp.
Definition at line 233 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::stopSegmentation | ( | ) | [protected] |
Definition at line 363 of file object_segmentation_rviz_ui.cpp.
int object_segmentation_gui::ObjectSegmentationRvizUI::sumLabels | ( | const sensor_msgs::Image & | image | ) | [private] |
Definition at line 438 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::uniformChecked | ( | ) | [protected, virtual, slot] |
Definition at line 984 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::update | ( | float | wall_dt, |
float | ros_dt | ||
) | [virtual] |
Definition at line 408 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 735 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::withColorChecked | ( | ) | [protected, virtual, slot] |
Definition at line 965 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::withDisparityChecked | ( | ) | [protected, virtual, slot] |
Definition at line 954 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::withHolesChecked | ( | ) | [protected, virtual, slot] |
Definition at line 981 of file object_segmentation_rviz_ui.cpp.
void object_segmentation_gui::ObjectSegmentationRvizUI::withSurfaceChecked | ( | ) | [protected, virtual, slot] |
Definition at line 951 of file object_segmentation_rviz_ui.cpp.
double object_segmentation_gui::ObjectSegmentationRvizUI::ball_size_ [private] |
Definition at line 191 of file object_segmentation_rviz_ui.h.
Ogre::ManualObject* object_segmentation_gui::ObjectSegmentationRvizUI::box_object_ [protected] |
Definition at line 145 of file object_segmentation_rviz_ui.h.
Definition at line 144 of file object_segmentation_rviz_ui.h.
voxel grid filtering parameters
Definition at line 259 of file object_segmentation_rviz_ui.h.
std::vector<sensor_msgs::PointCloud> object_segmentation_gui::ObjectSegmentationRvizUI::clusters_ [private] |
Point clusters
Definition at line 238 of file object_segmentation_rviz_ui.h.
Definition at line 229 of file object_segmentation_rviz_ui.h.
sensor_msgs::CameraInfo object_segmentation_gui::ObjectSegmentationRvizUI::current_camera_info_ [private] |
Definition at line 214 of file object_segmentation_rviz_ui.h.
stereo_msgs::DisparityImage object_segmentation_gui::ObjectSegmentationRvizUI::current_disparity_image_ [private] |
Definition at line 212 of file object_segmentation_rviz_ui.h.
sensor_msgs::Image object_segmentation_gui::ObjectSegmentationRvizUI::current_image_ [private] |
Definition at line 211 of file object_segmentation_rviz_ui.h.
The current marker being published.
Definition at line 248 of file object_segmentation_rviz_ui.h.
sensor_msgs::PointCloud2 object_segmentation_gui::ObjectSegmentationRvizUI::current_point_cloud_ [private] |
Definition at line 213 of file object_segmentation_rviz_ui.h.
double object_segmentation_gui::ObjectSegmentationRvizUI::grad_weight_ [private] |
Definition at line 189 of file object_segmentation_rviz_ui.h.
rviz_interaction_tools::ImageOverlay* object_segmentation_gui::ObjectSegmentationRvizUI::image_overlay_ [protected] |
Definition at line 128 of file object_segmentation_rviz_ui.h.
Publishing images (for debug only)
Definition at line 160 of file object_segmentation_rviz_ui.h.
sensor_msgs::Image object_segmentation_gui::ObjectSegmentationRvizUI::inits_ [private] |
Definition at line 220 of file object_segmentation_rviz_ui.h.
parameters for table plane detection
Definition at line 251 of file object_segmentation_rviz_ui.h.
sensor_msgs::Image object_segmentation_gui::ObjectSegmentationRvizUI::labels_ [private] |
Definition at line 217 of file object_segmentation_rviz_ui.h.
Publisher for markers.
Definition at line 244 of file object_segmentation_rviz_ui.h.
double object_segmentation_gui::ObjectSegmentationRvizUI::mean_k_ [private] |
statistical outlier removal parameters
Definition at line 255 of file object_segmentation_rviz_ui.h.
Definition at line 192 of file object_segmentation_rviz_ui.h.
The node handle.
Definition at line 154 of file object_segmentation_rviz_ui.h.
Definition at line 199 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 246 of file object_segmentation_rviz_ui.h.
actionlib::SimpleActionServer<ObjectSegmentationGuiAction>* object_segmentation_gui::ObjectSegmentationRvizUI::object_segmentation_server_ [protected] |
Definition at line 147 of file object_segmentation_rviz_ui.h.
Definition at line 196 of file object_segmentation_rviz_ui.h.
Definition at line 226 of file object_segmentation_rviz_ui.h.
std::deque<ObjectSegmenter::Box2D> object_segmentation_gui::ObjectSegmentationRvizUI::previous_queue_ [private] |
Definition at line 205 of file object_segmentation_rviz_ui.h.
The node handle.
Definition at line 157 of file object_segmentation_rviz_ui.h.
std::deque<ObjectSegmenter::Box2D> object_segmentation_gui::ObjectSegmentationRvizUI::region_queue_ [private] |
Definition at line 202 of file object_segmentation_rviz_ui.h.
Definition at line 123 of file object_segmentation_rviz_ui.h.
Definition at line 225 of file object_segmentation_rviz_ui.h.
Ogre::SceneManager* object_segmentation_gui::ObjectSegmentationRvizUI::scene_manager_ [protected] |
Definition at line 125 of file object_segmentation_rviz_ui.h.
Ogre::SceneNode* object_segmentation_gui::ObjectSegmentationRvizUI::scene_root_ [protected] |
Definition at line 126 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 235 of file object_segmentation_rviz_ui.h.
double object_segmentation_gui::ObjectSegmentationRvizUI::std_ [private] |
Definition at line 256 of file object_segmentation_rviz_ui.h.
Point belonging to table plane
Definition at line 241 of file object_segmentation_rviz_ui.h.
Definition at line 208 of file object_segmentation_rviz_ui.h.
sensor_msgs::Image object_segmentation_gui::ObjectSegmentationRvizUI::texture_buffer_ [private] |
Definition at line 223 of file object_segmentation_rviz_ui.h.
Ui::MainFrame* object_segmentation_gui::ObjectSegmentationRvizUI::ui_ [private] |
Definition at line 261 of file object_segmentation_rviz_ui.h.
double object_segmentation_gui::ObjectSegmentationRvizUI::up_direction_ [private] |
Definition at line 252 of file object_segmentation_rviz_ui.h.
Definition at line 193 of file object_segmentation_rviz_ui.h.
rviz::WindowManagerInterface* object_segmentation_gui::ObjectSegmentationRvizUI::window_manager_ [protected] |
Definition at line 122 of file object_segmentation_rviz_ui.h.
double object_segmentation_gui::ObjectSegmentationRvizUI::window_size_ [private] |
Definition at line 190 of file object_segmentation_rviz_ui.h.