$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2011, Robert Bosch LLC. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Robert Bosch nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 *********************************************************************/ 00036 00037 #ifndef OBJECT_SEGMENTATION_UI 00038 #define OBJECT_SEGMENTATION_UI 00039 00040 #include <ros/ros.h> 00041 00042 //#include "bosch_object_segmentation_gui/ObjectSegmentationGuiAction.h" 00043 #include <actionlib/server/simple_action_server.h> 00044 00045 #include "image_segmentation_demo/grabcut3d_object_segmenter.h" 00046 #include "image_segmentation_demo/table_detector.h" 00047 00048 #include <tf/transform_listener.h> 00049 #include <visualization_msgs/Marker.h> 00050 #include <tabletop_object_detector/TabletopDetection.h> 00051 00052 #include <wx/event.h> 00053 00054 //#include <rviz/visualization_manager.h> 00055 #include <OGRE/OgreManualObject.h> 00056 00057 #include <sensor_msgs/CameraInfo.h> 00058 #include <stereo_msgs/DisparityImage.h> 00059 00060 #include "object_segmentation_frame.h" 00061 #include <image_transport/image_transport.h> 00062 00063 namespace rviz_interaction_tools { 00064 class ImageOverlay; 00065 class DisparityRenderer; 00066 } 00067 00068 namespace rviz { 00069 class WindowManagerInterface; 00070 class RenderPanel; 00071 } 00072 00073 namespace image_segmentation_demo { 00074 00075 class ObjectSegmentationUI : public ObjectSegmentationFrame 00076 { 00077 typedef geometry_msgs::Point32 Point; 00078 00079 public: 00080 ObjectSegmentationUI(); 00081 virtual ~ObjectSegmentationUI(); 00082 00083 virtual void update(float wall_dt, float ros_dt); 00084 00085 00086 //start listening to action goals 00087 // void startActionServer( ros::NodeHandle &node_handle ); 00088 00089 //stop action server, cancel current goal & hide if necessary 00090 // void stopActionServer(); 00091 00092 protected: 00093 00094 // callback for new action server goals 00095 // void acceptNewGoal(); 00096 00097 // callback for action server preempt (cancel) requests 00098 // void preempt(); 00099 00100 virtual void onRenderWindowMouseEvents( wxMouseEvent& event ); 00101 00102 // button events 00103 virtual void acceptButtonClicked( wxCommandEvent& ); 00104 virtual void cancelButtonClicked( wxCommandEvent& ); 00105 virtual void resetButtonClicked( wxCommandEvent& ); 00106 virtual void segmentButtonClicked( wxCommandEvent& ); 00107 00108 //cleanup ogre scene, hide window 00109 void cleanupAndHide(); 00110 00111 // stop segmentation by sending a stop message 00112 void stopSegmentation(); 00113 00114 //put ogre panel into the window 00115 void createRenderPanel(); 00116 00117 rviz::WindowManagerInterface* window_manager_; 00118 rviz::RenderPanel* render_panel_; 00119 00120 Ogre::SceneManager* scene_manager_; 00121 Ogre::SceneNode* scene_root_; 00122 00123 rviz_interaction_tools::ImageOverlay* image_overlay_; 00124 00125 void reconstructAndClusterPointCloud(tabletop_object_detector::TabletopDetection &result); 00126 00127 00128 // actionlib::SimpleActionServer<ObjectSegmentationGuiAction> *object_segmentation_server_; 00129 00130 private: 00131 00132 enum ResetType{PLAIN, COLOR, SURFACE, DISP, HOLES, UNIFORM}; 00133 00135 ros::NodeHandle nh_; 00136 00138 ros::NodeHandle priv_nh_; 00139 00141 image_transport::Publisher image_pub_; 00142 00143 // overlays current result from segmenter with image from camera 00144 void overlaySegmentationMask(); 00145 00146 // creates an RGB image from point cloud that comes in 00147 void fillRgbImage(sensor_msgs::Image &rgb_img, 00148 const sensor_msgs::PointCloud2 &point_cloud); 00149 00150 // get a single depth image 00151 bool getDepthImage(sensor_msgs::Image& image_msg); 00152 // convert image message to cv 00153 bool convertImageMessageToMat(const sensor_msgs::Image& image_msg, Mat& image); 00154 // convert cv to image message 00155 bool convertMatToImageMessage(const Mat& image, sensor_msgs::Image& image_msg); 00156 // update display image 00157 void updateImageOverlay(); 00158 // reset internal state 00159 void resetVars( ); 00160 00161 00162 // Segmentation object 00163 GrabCut3DObjectSegmenter* object_segmenter_; 00164 00165 // detect table 00166 TableDetector table_detector_; 00167 00168 // stores sensor data 00169 sensor_msgs::Image current_image_; 00170 sensor_msgs::Image current_depth_image_; 00171 stereo_msgs::DisparityImage current_disparity_image_; 00172 sensor_msgs::PointCloud2 current_point_cloud_; 00173 sensor_msgs::CameraInfo current_camera_info_; 00174 00175 // segmentation mask 00176 cv::Mat binary_mask_; 00177 00179 std::vector<sensor_msgs::PointCloud> clusters_; 00180 00182 ros::Publisher marker_pub_; 00184 int num_markers_published_; 00186 int current_marker_id_; 00187 }; 00188 00189 } 00190 00191 #endif