$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 00038 00039 #ifndef OBJECT_SEGMENTATION_UI 00040 #define OBJECT_SEGMENTATION_UI 00041 00042 #include <wx/wx.h> 00043 #include <wx/event.h> 00044 00045 #include <ros/ros.h> 00046 #include <time.h> 00047 #include <tabletop_object_detector/TabletopDetection.h> 00048 #include <tabletop_object_detector/TabletopDetectionResult.h> 00049 #include <tabletop_collision_map_processing/TabletopCollisionMapProcessing.h> 00050 #include <object_manipulation_msgs/PickupAction.h> 00051 #include <object_manipulation_msgs/PlaceAction.h> 00052 #include <actionlib/client/simple_action_client.h> 00053 #include <rgbd_assembler/RgbdAssembly.h> 00054 00055 #include <simple_robot_control/robot_control.h> 00056 00057 #include "ogre_tools/wx_ogre_render_window.h" 00058 #include "ogre_tools/initialization.h" 00059 00060 #include <boost/shared_ptr.hpp> 00061 #include <OGRE/OgreRoot.h> 00062 #include <OGRE/OgreSceneManager.h> 00063 #include <OGRE/OgreViewport.h> 00064 #include <OGRE/OgreRectangle2D.h> 00065 #include <OGRE/OgreMaterial.h> 00066 #include <OGRE/OgreMaterialManager.h> 00067 #include <OGRE/OgreTextureUnitState.h> 00068 00069 00070 #include "image_segmentation_demo/grabcut3d_object_segmenter.h" 00071 #include "image_segmentation_demo/table_detector.h" 00072 #include "image_segmentation_demo/ros_image_texture.h" 00073 #include "object_segmentation_frame.h" 00074 00075 namespace image_segmentation_demo { 00076 00077 class ObjectSegmentationUI : public ObjectSegmentationFrame 00078 { 00079 public: 00080 ObjectSegmentationUI(wxWindow* parentwindow); 00081 virtual ~ObjectSegmentationUI(); 00082 virtual void acceptButtonClicked( wxCommandEvent& ); 00083 virtual void cancelButtonClicked( wxCommandEvent& ); 00084 virtual void resetButtonClicked( wxCommandEvent& ); 00085 virtual void segmentButtonClicked( wxCommandEvent& ); 00086 virtual void refreshButtonClicked(wxCommandEvent&); 00087 virtual void onRenderWindowMouseEvents( wxMouseEvent& event ); 00088 virtual void update(float wall_dt, float ros_dt); 00089 void cleanupAndQuit(); 00090 private: 00091 00092 Ogre::Root* root_; 00093 Ogre::SceneManager* scene_manager_; 00094 ogre_tools::wxOgreRenderWindow* render_window_; 00095 Ogre::Camera* camera_; 00096 00098 ros::NodeHandlePtr nh; 00099 ros::Publisher chatter_pub; 00100 00101 00102 std::string OBJECT_DETECTION_SERVICE_NAME; 00103 std::string COLLISION_PROCESSING_SERVICE_NAME; 00104 std::string PICKUP_ACTION_NAME; 00105 std::string PLACE_ACTION_NAME; 00106 std::string RGBD_ASSEMBLY_SERVICE_NAME; 00107 std::string ARM_ACTION_NAME; 00108 00109 std::string data_location_; 00110 bool recording_time_; 00111 time_t start_time_; 00112 time_t stop_time_; 00113 std::string data_string_; 00114 int num_resets_; 00115 bool object_grasp_; 00116 00117 ros::ServiceClient rgbd_assembler_client_; 00118 ros::ServiceClient object_detection_srv; 00119 ros::ServiceClient collision_processing_srv; 00120 00121 // collection of the sensor data 00122 sensor_msgs::Image current_image_; 00123 sensor_msgs::Image display_image_; 00124 sensor_msgs::Image current_depth_image_; 00125 stereo_msgs::DisparityImage current_disparity_image_; 00126 sensor_msgs::CameraInfo current_camera_info_; 00127 sensor_msgs::PointCloud2 current_point_cloud_; 00128 00129 // Segmentation object 00130 GrabCut3DObjectSegmenter* object_segmenter_; 00131 00133 tf::TransformListener listener_; 00134 // detect table 00135 TableDetector table_detector_; 00136 tabletop_object_detector::TabletopDetectionResult detection_call_; 00137 ROSImageTexture* texture_; 00138 00139 rgbd_assembler::RgbdAssembly rgbd_assembler_srv_; 00140 00141 simple_robot_control::Robot robot_; 00142 00143 actionlib::SimpleActionClient<object_manipulation_msgs::PickupAction> *pickup_client; 00144 actionlib::SimpleActionClient<object_manipulation_msgs::PlaceAction> *place_client; 00145 00146 00147 // segmentation mask 00148 cv::Mat binary_mask_; 00149 00150 00152 std::vector<sensor_msgs::PointCloud> clusters_; 00153 00155 ros::Publisher marker_pub_; 00157 int num_markers_published_; 00159 int current_marker_id_; 00160 00161 00162 // creates an RGB image from point cloud that comes in 00163 void fillRgbImage(sensor_msgs::Image &rgb_img, const sensor_msgs::PointCloud2 &point_cloud); 00164 void setUpEventHandlers(); 00165 void update(); 00166 bool GetSensorData(); 00167 bool getDepthImage(sensor_msgs::Image& image_msg); 00168 void SetUpPickandPlaceApp(); 00169 void RunRestOfPickAndPlace(); 00170 void updateImageOverlay(); 00171 void updateView(); 00172 void saveData(); 00173 // convert cv to image message 00174 bool convertMatToImageMessage(const Mat& image, sensor_msgs::Image& image_msg); 00175 bool convertImageMessageToMat(const sensor_msgs::Image& image_msg, Mat& image); 00176 void resetVars(); 00177 void reconstructAndClusterPointCloud(); 00178 bool transformPointCloud(const std::string &target_frame, const sensor_msgs::PointCloud2& cloud_in, sensor_msgs::PointCloud2& cloud_out); 00179 }; 00180 00181 } 00182 #endif