$search
00001 /* 00002 * Copyright (c) 2009, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #ifndef OBJECT_SEGMENTATION_RVIZ_UI 00031 #define OBJECT_SEGMENTATION_RVIZ_UI 00032 00033 #include <ros/ros.h> 00034 00035 #include "object_segmentation_gui/ObjectSegmentationGuiAction.h" 00036 #include <actionlib/server/simple_action_server.h> 00037 00038 #include "object_segmentation_gui/object_segmenter.h" 00039 #include "object_segmentation_gui/table_transform.h" 00040 00041 #include <tf/transform_listener.h> 00042 #include <visualization_msgs/Marker.h> 00043 00044 #include <wx/event.h> 00045 00046 #include <rviz/visualization_manager.h> 00047 #include <OGRE/OgreManualObject.h> 00048 00049 #include <sensor_msgs/CameraInfo.h> 00050 00051 #include "object_segmentation_frame.h" 00052 #include <image_transport/image_transport.h> 00053 00054 namespace rviz_interaction_tools { 00055 class ImageOverlay; 00056 class DisparityRenderer; 00057 } 00058 00059 namespace rviz { 00060 class WindowManagerInterface; 00061 class RenderPanel; 00062 } 00063 00064 00065 namespace object_segmentation_gui { 00066 00067 class ObjectSegmentationRvizUI : public ObjectSegmentationFrame 00068 { 00069 typedef geometry_msgs::Point32 Point; 00070 00071 public: 00072 ObjectSegmentationRvizUI(rviz::VisualizationManager *visualization_manager); 00073 virtual ~ObjectSegmentationRvizUI(); 00074 00075 virtual void update(float wall_dt, float ros_dt); 00076 00077 //start listening to action goals 00078 void startActionServer( ros::NodeHandle &node_handle ); 00079 00080 //stop action server, cancel current goal & hide if necessary 00081 void stopActionServer(); 00082 00083 protected: 00084 00085 // callback for new action server goals 00086 void acceptNewGoal(); 00087 00088 // callback for action server preempt (cancel) requests 00089 void preempt(); 00090 00091 virtual void onRenderWindowMouseEvents( wxMouseEvent& event ); 00092 00093 virtual void acceptButtonClicked( wxCommandEvent& ); 00094 virtual void cancelButtonClicked( wxCommandEvent& ); 00095 00096 virtual void resetButtonClicked( wxCommandEvent& ); 00097 virtual void restartButtonClicked( wxCommandEvent& event ); 00098 virtual void segmentButtonClicked( wxCommandEvent& ); 00099 00100 virtual void withSurfaceChecked( wxCommandEvent& event ) ; 00101 virtual void withDisparityChecked( wxCommandEvent& event ) ; 00102 virtual void withColorChecked( wxCommandEvent& event ) ; 00103 virtual void withHolesChecked( wxCommandEvent& event ) ; 00104 virtual void uniformChecked( wxCommandEvent& event ) ; 00105 00106 virtual void gradWeightChanged( wxScrollEvent& event ); 00107 00108 00109 //cleanup ogre scene, hide window 00110 void cleanupAndHide(); 00111 00112 // stop segmentation by sending a stop message 00113 void stopSegmentation(); 00114 00115 //put ogre panel into the window 00116 void createRenderPanel( rviz::VisualizationManager *visualization_manager ); 00117 00118 rviz::WindowManagerInterface* window_manager_; 00119 rviz::RenderPanel* render_panel_; 00120 00121 Ogre::SceneManager* scene_manager_; 00122 Ogre::SceneNode* scene_root_; 00123 00124 rviz_interaction_tools::ImageOverlay* image_overlay_; 00125 00126 struct ClickInfo 00127 { 00128 int x_, y_; 00129 int down_x_, down_y_; 00130 bool down_; 00131 bool dragged_; 00132 }; 00133 00134 void addColorCode(); 00135 00136 void reconstructAndClusterPointCloud(ObjectSegmentationGuiResult &result); 00137 00138 void filterOutliersAndDownsample(std::vector<sensor_msgs::PointCloud> &clusters); 00139 00140 ClickInfo click_info_; 00141 Ogre::ManualObject* box_object_; 00142 00143 actionlib::SimpleActionServer<ObjectSegmentationGuiAction> *object_segmentation_server_; 00144 00145 private: 00146 00147 enum ResetType{PLAIN, COLOR, SURFACE, DISP, HOLES, UNIFORM}; 00148 00150 ros::NodeHandle nh_; 00151 00153 ros::NodeHandle priv_nh_; 00154 00156 image_transport::Publisher image_pub_; 00157 00158 // overlays current result from segmenter with image from camera 00159 void overlaySegmentationMask(); 00160 00161 // calculates the number of points in each segment 00162 void getClusterSize(); 00163 00164 // creates an image of selected region to be overlayed with current camera image 00165 void addToMasks(const ObjectSegmenter::Box2D &select_); 00166 00167 // upates the select box during mouse dragging 00168 void updateSelectBox(int start_x, int start_y, int stop_x, int stop_y); 00169 00170 // creates an RGB image from point cloud that comes in 00171 void fillRgbImage(sensor_msgs::Image &rgb_img, 00172 const sensor_msgs::PointCloud2 &point_cloud); 00173 00174 void initStorage(const sensor_msgs::Image &image); 00175 00176 void segment(); 00177 00178 void reset(); 00179 void includeFlags( ObjectSegmenter::Action &ac ); 00180 void resetVars( ); 00181 00182 int sumLabels( const sensor_msgs::Image &image); 00183 00184 // Parameters of object segmentation 00185 double grad_weight_; 00186 double window_size_; 00187 double ball_size_; 00188 int n_iter_; 00189 bool use_gpu_; 00190 00191 // Segmentation object 00192 ObjectSegmenter* object_segmenter_; 00193 00194 // Number of foreground hypotheses 00195 int num_fg_hypos_; 00196 00197 // stores most recent selected regions or points 00198 std::deque<ObjectSegmenter::Box2D> region_queue_; 00199 00200 // stores previous selected regions or points for potential replaying 00201 std::deque<ObjectSegmenter::Box2D> previous_queue_; 00202 00203 // transform table in (x, y, d) space to (x, y, z) space 00204 TableTransform table_transformer_; 00205 00206 // stores sensor data 00207 sensor_msgs::Image current_image_; 00208 stereo_msgs::DisparityImage current_disparity_image_; 00209 sensor_msgs::PointCloud2 current_point_cloud_; 00210 sensor_msgs::CameraInfo current_camera_info_; 00211 00212 // segmentation mask 00213 sensor_msgs::Image labels_; 00214 00215 // initialisation mask 00216 sensor_msgs::Image inits_; 00217 00218 // stores feedback image in display 00219 sensor_msgs::Image texture_buffer_; 00220 00221 bool running_; 00222 bool paused_; 00223 00224 // Color code for each segment (RGB) 00225 std::vector<int> color_code_; 00226 00231 std::vector<int> segm_size_; 00232 00234 std::vector<sensor_msgs::PointCloud> clusters_; 00235 00237 sensor_msgs::PointCloud table_points_; 00238 00240 ros::Publisher marker_pub_; 00242 int num_markers_published_; 00244 int current_marker_id_; 00245 00247 int inlier_threshold_; 00248 double up_direction_; 00249 00251 double mean_k_; 00252 double std_; 00253 00255 double clustering_voxel_size_; 00256 }; 00257 00258 } 00259 00260 #endif