Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef OBJECT_SEGMENTATION_RVIZ_UI
00031 #define OBJECT_SEGMENTATION_RVIZ_UI
00032
00033 #include <QWidget>
00034
00035 #include <ros/ros.h>
00036
00037 #include "object_segmentation_gui/ObjectSegmentationGuiAction.h"
00038 #include <actionlib/server/simple_action_server.h>
00039
00040 #include "object_segmentation_gui/object_segmenter.h"
00041 #include "object_segmentation_gui/table_transform.h"
00042
00043 #include <tf/transform_listener.h>
00044 #include <visualization_msgs/Marker.h>
00045
00046 #include <OGRE/OgreManualObject.h>
00047
00048 #include <sensor_msgs/CameraInfo.h>
00049
00050 #include <image_transport/image_transport.h>
00051
00052 namespace rviz_interaction_tools {
00053 class ImageOverlay;
00054 class DisparityRenderer;
00055 }
00056
00057 namespace rviz {
00058 class WindowManagerInterface;
00059 class RenderPanel;
00060 class VisualizationManager;
00061 }
00062
00063 namespace Ui {
00064 class MainFrame;
00065 }
00066
00067 namespace object_segmentation_gui {
00068
00069 class ObjectSegmentationRvizUI : public QWidget
00070 {
00071 Q_OBJECT
00072 typedef geometry_msgs::Point32 Point;
00073
00074 public:
00075 ObjectSegmentationRvizUI( rviz::VisualizationManager* visualization_manager, QWidget* parent = 0 );
00076 virtual ~ObjectSegmentationRvizUI();
00077
00078 virtual void update(float wall_dt, float ros_dt);
00079
00080
00081 void startActionServer( ros::NodeHandle &node_handle );
00082
00083
00084 void stopActionServer();
00085
00086 protected Q_SLOTS:
00087 virtual void acceptButtonClicked();
00088 virtual void cancelButtonClicked();
00089
00090 virtual void resetButtonClicked();
00091 virtual void restartButtonClicked();
00092 virtual void segmentButtonClicked();
00093
00094 virtual void withSurfaceChecked() ;
00095 virtual void withDisparityChecked() ;
00096 virtual void withColorChecked() ;
00097 virtual void withHolesChecked() ;
00098 virtual void uniformChecked() ;
00099
00100 virtual void gradWeightChanged( int new_value );
00101
00102 protected:
00103
00104
00105 void acceptNewGoal();
00106
00107
00108 void preempt();
00109
00111 virtual bool eventFilter( QObject* watched_object, QEvent* event );
00112
00113
00114 void cleanupAndHide();
00115
00116
00117 void stopSegmentation();
00118
00119
00120 void setupRenderPanel( rviz::VisualizationManager *visualization_manager );
00121
00122 rviz::WindowManagerInterface* window_manager_;
00123 rviz::RenderPanel* render_panel_;
00124
00125 Ogre::SceneManager* scene_manager_;
00126 Ogre::SceneNode* scene_root_;
00127
00128 rviz_interaction_tools::ImageOverlay* image_overlay_;
00129
00130 struct ClickInfo
00131 {
00132 int x_, y_;
00133 int down_x_, down_y_;
00134 bool down_;
00135 bool dragged_;
00136 };
00137
00138 void addColorCode();
00139
00140 void reconstructAndClusterPointCloud(ObjectSegmentationGuiResult &result);
00141
00142 void filterOutliersAndDownsample(std::vector<sensor_msgs::PointCloud> &clusters);
00143
00144 ClickInfo click_info_;
00145 Ogre::ManualObject* box_object_;
00146
00147 actionlib::SimpleActionServer<ObjectSegmentationGuiAction> *object_segmentation_server_;
00148
00149 private:
00150
00151 enum ResetType{PLAIN, COLOR, SURFACE, DISP, HOLES, UNIFORM};
00152
00154 ros::NodeHandle nh_;
00155
00157 ros::NodeHandle priv_nh_;
00158
00160 image_transport::Publisher image_pub_;
00161
00162
00163 void overlaySegmentationMask();
00164
00165
00166 void getClusterSize();
00167
00168
00169 void addToMasks(const ObjectSegmenter::Box2D &select_);
00170
00171
00172 void updateSelectBox(int start_x, int start_y, int stop_x, int stop_y);
00173
00174
00175 void fillRgbImage(sensor_msgs::Image &rgb_img,
00176 const sensor_msgs::PointCloud2 &point_cloud);
00177
00178 void initStorage(const sensor_msgs::Image &image);
00179
00180 void segment();
00181
00182 void reset();
00183 void includeFlags( ObjectSegmenter::Action &ac );
00184 void resetVars( );
00185
00186 int sumLabels( const sensor_msgs::Image &image);
00187
00188
00189 double grad_weight_;
00190 double window_size_;
00191 double ball_size_;
00192 int n_iter_;
00193 bool use_gpu_;
00194
00195
00196 ObjectSegmenter* object_segmenter_;
00197
00198
00199 int num_fg_hypos_;
00200
00201
00202 std::deque<ObjectSegmenter::Box2D> region_queue_;
00203
00204
00205 std::deque<ObjectSegmenter::Box2D> previous_queue_;
00206
00207
00208 TableTransform table_transformer_;
00209
00210
00211 sensor_msgs::Image current_image_;
00212 stereo_msgs::DisparityImage current_disparity_image_;
00213 sensor_msgs::PointCloud2 current_point_cloud_;
00214 sensor_msgs::CameraInfo current_camera_info_;
00215
00216
00217 sensor_msgs::Image labels_;
00218
00219
00220 sensor_msgs::Image inits_;
00221
00222
00223 sensor_msgs::Image texture_buffer_;
00224
00225 bool running_;
00226 bool paused_;
00227
00228
00229 std::vector<int> color_code_;
00230
00235 std::vector<int> segm_size_;
00236
00238 std::vector<sensor_msgs::PointCloud> clusters_;
00239
00241 sensor_msgs::PointCloud table_points_;
00242
00244 ros::Publisher marker_pub_;
00246 int num_markers_published_;
00248 int current_marker_id_;
00249
00251 int inlier_threshold_;
00252 double up_direction_;
00253
00255 double mean_k_;
00256 double std_;
00257
00259 double clustering_voxel_size_;
00260
00261 Ui::MainFrame *ui_;
00262 };
00263
00264 }
00265
00266 #endif