$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_RVIZ_UI 00038 #define OBJECT_SEGMENTATION_RVIZ_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 "bosch_object_segmentation_gui/grabcut3d_object_segmenter.h" 00046 #include "bosch_object_segmentation_gui/table_detector.h" 00047 00048 #include <tf/transform_listener.h> 00049 #include <visualization_msgs/Marker.h> 00050 00051 #include <wx/event.h> 00052 00053 #include <rviz/visualization_manager.h> 00054 #include <OGRE/OgreManualObject.h> 00055 00056 #include <sensor_msgs/CameraInfo.h> 00057 00058 #include "object_segmentation_frame.h" 00059 #include <image_transport/image_transport.h> 00060 00061 namespace rviz_interaction_tools { 00062 class ImageOverlay; 00063 class DisparityRenderer; 00064 } 00065 00066 namespace rviz { 00067 class WindowManagerInterface; 00068 class RenderPanel; 00069 } 00070 00071 namespace bosch_object_segmentation_gui { 00072 00073 class ObjectSegmentationRvizUI : public ObjectSegmentationFrame 00074 { 00075 typedef geometry_msgs::Point32 Point; 00076 00077 public: 00078 ObjectSegmentationRvizUI(rviz::VisualizationManager *visualization_manager); 00079 virtual ~ObjectSegmentationRvizUI(); 00080 00081 virtual void update(float wall_dt, float ros_dt); 00082 00083 //start listening to action goals 00084 void startActionServer( ros::NodeHandle &node_handle ); 00085 00086 //stop action server, cancel current goal & hide if necessary 00087 void stopActionServer(); 00088 00089 protected: 00090 00091 // callback for new action server goals 00092 void acceptNewGoal(); 00093 00094 // callback for action server preempt (cancel) requests 00095 void preempt(); 00096 00097 virtual void onRenderWindowMouseEvents( wxMouseEvent& event ); 00098 00099 // button events 00100 virtual void acceptButtonClicked( wxCommandEvent& ); 00101 virtual void cancelButtonClicked( wxCommandEvent& ); 00102 virtual void resetButtonClicked( wxCommandEvent& ); 00103 virtual void segmentButtonClicked( wxCommandEvent& ); 00104 00105 //cleanup ogre scene, hide window 00106 void cleanupAndHide(); 00107 00108 // stop segmentation by sending a stop message 00109 void stopSegmentation(); 00110 00111 //put ogre panel into the window 00112 void createRenderPanel( rviz::VisualizationManager *visualization_manager ); 00113 00114 rviz::WindowManagerInterface* window_manager_; 00115 rviz::RenderPanel* render_panel_; 00116 00117 Ogre::SceneManager* scene_manager_; 00118 Ogre::SceneNode* scene_root_; 00119 00120 rviz_interaction_tools::ImageOverlay* image_overlay_; 00121 00122 void reconstructAndClusterPointCloud(ObjectSegmentationGuiResult &result); 00123 00124 actionlib::SimpleActionServer<ObjectSegmentationGuiAction> *object_segmentation_server_; 00125 00126 private: 00127 00128 enum ResetType{PLAIN, COLOR, SURFACE, DISP, HOLES, UNIFORM}; 00129 00131 ros::NodeHandle nh_; 00132 00134 ros::NodeHandle priv_nh_; 00135 00137 image_transport::Publisher image_pub_; 00138 00139 // overlays current result from segmenter with image from camera 00140 void overlaySegmentationMask(); 00141 00142 // creates an RGB image from point cloud that comes in 00143 void fillRgbImage(sensor_msgs::Image &rgb_img, 00144 const sensor_msgs::PointCloud2 &point_cloud); 00145 00146 // get a single depth image 00147 bool getDepthImage(sensor_msgs::Image& image_msg); 00148 // convert image message to cv 00149 bool convertImageMessageToMat(const sensor_msgs::Image& image_msg, Mat& image); 00150 // convert cv to image message 00151 bool convertMatToImageMessage(const Mat& image, sensor_msgs::Image& image_msg); 00152 // update display image 00153 void updateImageOverlay(); 00154 // reset internal state 00155 void resetVars( ); 00156 00157 00158 // Segmentation object 00159 GrabCut3DObjectSegmenter* object_segmenter_; 00160 00161 // detect table 00162 TableDetector table_detector_; 00163 00164 // stores sensor data 00165 sensor_msgs::Image current_image_; 00166 sensor_msgs::Image current_depth_image_; 00167 stereo_msgs::DisparityImage current_disparity_image_; 00168 sensor_msgs::PointCloud2 current_point_cloud_; 00169 sensor_msgs::CameraInfo current_camera_info_; 00170 00171 // segmentation mask 00172 cv::Mat binary_mask_; 00173 00175 std::vector<sensor_msgs::PointCloud> clusters_; 00176 00178 ros::Publisher marker_pub_; 00180 int num_markers_published_; 00182 int current_marker_id_; 00183 }; 00184 00185 } 00186 00187 #endif