$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 #include "pr2_interactive_manipulation/graspable_object_handler.h" 00031 00032 #include <visualization_msgs/InteractiveMarker.h> 00033 #include <visualization_msgs/InteractiveMarkerFeedback.h> 00034 00035 #include "pr2_interactive_manipulation/interactive_marker_node.h" 00036 00037 using namespace visualization_msgs; 00038 using namespace interactive_markers; 00039 00040 namespace pr2_interactive_manipulation 00041 { 00042 00043 GraspableObjectHandler::GraspableObjectHandler( std::string name, 00044 InteractiveMarkerNode *node, 00045 const object_manipulation_msgs::GraspableObject &object, 00046 const arm_navigation_msgs::Shape &mesh, 00047 interactive_markers::InteractiveMarkerServer &marker_server, 00048 pr2_object_manipulation_msgs::IMGUIOptions &options, 00049 tabletop_collision_map_processing::CollisionMapInterface *col ) : 00050 marker_server_(marker_server), 00051 im_gui_action_client_("imgui_action", false), 00052 options_(options), 00053 object_(object), 00054 mesh_(mesh), 00055 use_rec_result_(true), 00056 collision_map_interface_(col), 00057 use_rec_result_h_(0), 00058 name_(name), 00059 interactive_marker_node_(node) 00060 { 00061 makeMenu(); 00062 makeMarker(); 00063 } 00064 00065 GraspableObjectHandler::~GraspableObjectHandler() 00066 { 00067 marker_server_.erase(name_); 00068 } 00069 00070 void GraspableObjectHandler::makeMenu() 00071 { 00072 // create menu 00073 MenuHandler::EntryHandle pickup_h = menu_handler_.insert( "Pick Up" ); 00074 left_pickup_h_ = menu_handler_.insert( pickup_h, "Using Left Arm", 00075 boost::bind( &GraspableObjectHandler::pickup, this, _1) ); 00076 right_pickup_h_ = menu_handler_.insert( pickup_h, "Using Right Arm", 00077 boost::bind( &GraspableObjectHandler::pickup, this, _1) ); 00078 00079 add_collision_object_h_ = menu_handler_.insert("Add Collision Object", 00080 boost::bind( &GraspableObjectHandler::addCollisionObject, this, _1)); 00081 00082 // only add choice if there is actually one 00083 if ( mesh_.triangles.size() > 0 && object_.cluster.points.size() > 0 ) 00084 { 00085 use_rec_result_h_ = menu_handler_.insert( "Use Recognition Result", 00086 boost::bind( &GraspableObjectHandler::switchFlag, this, &use_rec_result_, _1) ); 00087 } 00088 00089 menu_handler_.insert( "Advanced options..", 00090 visualization_msgs::MenuEntry::ROSRUN, 00091 "dynamic_reconfigure reconfigure_gui " + ros::this_node::getName() ); 00092 00093 updateMenu(); 00094 } 00095 00096 void GraspableObjectHandler::updateMenu() 00097 { 00098 if ( use_rec_result_h_ ) 00099 { 00100 menu_handler_.setCheckState( use_rec_result_h_, use_rec_result_ ? MenuHandler::CHECKED : MenuHandler::UNCHECKED ); 00101 } 00102 00103 menu_handler_.reApply( marker_server_ ); 00104 marker_server_.applyChanges(); 00105 } 00106 00107 void GraspableObjectHandler::addCollisionObject( const InteractiveMarkerFeedbackConstPtr &feedback ) 00108 { 00109 ros::Time start_time = ros::Time::now(); 00110 while (!collision_map_interface_->connectionsEstablished(ros::Duration(1.0)) ) 00111 { 00112 ROS_INFO("Waiting for collision map services"); 00113 if (ros::Time::now() - start_time >= ros::Duration(5.0)) 00114 { 00115 ROS_ERROR("collision map services not found"); 00116 return; 00117 } 00118 } 00119 try 00120 { 00121 if (!object_.potential_models.empty()) 00122 { 00123 collision_map_interface_->processCollisionGeometryForObject(object_.potential_models[0], collision_object_name_); 00124 } 00125 else 00126 { 00127 object_manipulation_msgs::ClusterBoundingBox bbox; 00128 collision_map_interface_->getClusterBoundingBox(object_.cluster, bbox.pose_stamped, bbox.dimensions); 00129 collision_map_interface_->processCollisionGeometryForBoundingBox(bbox, collision_object_name_); 00130 } 00131 } 00132 catch (tabletop_collision_map_processing::CollisionMapException &ex) 00133 { 00134 ROS_ERROR_STREAM("Exception adding object to collision map: " << ex.what()); 00135 return; 00136 } 00137 ROS_INFO_STREAM("Object added to collision map as " << collision_object_name_); 00138 object_.collision_name = collision_object_name_; 00139 } 00140 00141 void GraspableObjectHandler::pickup( const InteractiveMarkerFeedbackConstPtr &feedback ) 00142 { 00143 // determine arm selection 00144 MenuHandler::EntryHandle arm_h = feedback->menu_entry_id; 00145 if ( arm_h == left_pickup_h_ ) options_.arm_selection = 1; 00146 else if ( arm_h == right_pickup_h_ ) options_.arm_selection = 0; 00147 else return; 00148 00149 // pick up 00150 ROS_INFO_STREAM( "Picking up object # " << feedback->marker_name ); 00151 00152 object_manipulation_msgs::GraspableObject object = object_; 00153 00154 if ( !use_rec_result_ ) 00155 { 00156 object.potential_models.clear(); 00157 } 00158 00159 pr2_object_manipulation_msgs::IMGUIGoal goal; 00160 goal.options = options_; 00161 goal.options.grasp_selection = 1; 00162 goal.options.selected_object = object; 00163 goal.options.movable_obstacles = interactive_marker_node_->getMovableObstacles(); 00164 goal.command.command = goal.command.PICKUP; 00165 00166 im_gui_action_client_.sendGoal(goal); 00167 00168 marker_server_.clear(); 00169 marker_server_.applyChanges(); 00170 } 00171 00172 00173 void GraspableObjectHandler::makeMarker() 00174 { 00175 InteractiveMarker int_marker; 00176 int_marker.name = name_; 00177 00178 Marker marker; 00179 marker.color.r = 0.0; 00180 marker.color.g = 1.0; 00181 marker.color.b = 0.0; 00182 marker.color.a = 0.5; 00183 marker.frame_locked = false; 00184 00185 if ( use_rec_result_ && mesh_.type == arm_navigation_msgs::Shape::MESH && mesh_.vertices.size() > 0 ) 00186 { 00187 int_marker.pose = object_.potential_models[0].pose.pose; 00188 int_marker.header = object_.potential_models[0].pose.header; 00189 00190 marker.type = Marker::TRIANGLE_LIST; 00191 00192 ROS_INFO_STREAM( "Adding mesh. #triangles=" << mesh_.triangles.size() ); 00193 00194 marker.points.reserve( mesh_.triangles.size()*3 ); 00195 00196 size_t num_t = mesh_.triangles.size(); 00197 for ( size_t t=0; t+2<num_t; t+=3 ) 00198 { 00199 if ( (size_t)mesh_.triangles[t] < mesh_.vertices.size() && 00200 (size_t)mesh_.triangles[t+1] < mesh_.vertices.size() && 00201 (size_t)mesh_.triangles[t+2] < mesh_.vertices.size() ) 00202 { 00203 marker.points.push_back( mesh_.vertices[ mesh_.triangles[t] ] ); 00204 marker.points.push_back( mesh_.vertices[ mesh_.triangles[t+1] ] ); 00205 marker.points.push_back( mesh_.vertices[ mesh_.triangles[t+2] ] ); 00206 } 00207 else 00208 { 00209 ROS_ERROR("Mesh contains invalid triangle!"); 00210 break; 00211 } 00212 } 00213 } 00214 else 00215 { 00216 int_marker.header = object_.cluster.header; 00217 marker.scale.x = 0.005; 00218 marker.scale.y = 0.005; 00219 marker.scale.z = 0.005; 00220 marker.type = Marker::CUBE_LIST; 00221 00222 marker.points.resize( object_.cluster.points.size() ); 00223 marker.colors.resize( object_.cluster.points.size() ); 00224 00225 ROS_INFO_STREAM( "Adding point cluster. #points=" << object_.cluster.points.size() ); 00226 bool use_color = false; 00227 if(object_.cluster.channels.size() != 0 && object_.cluster.channels[0].name == "rgb") use_color = true; 00228 for ( size_t i=0; i<object_.cluster.points.size(); i++) 00229 { 00230 marker.points[i].x = object_.cluster.points[i].x; 00231 marker.points[i].y = object_.cluster.points[i].y; 00232 marker.points[i].z = object_.cluster.points[i].z; 00233 if(use_color) 00234 { 00235 uint32_t rgb = *reinterpret_cast<int*>(&object_.cluster.channels[0].values[i]); 00236 marker.colors[i].r = ((rgb >> 16) & 0x0000ff)/255. * 0.5; 00237 marker.colors[i].g = ((rgb >> 8) & 0x0000ff)/255. * 1.5; 00238 marker.colors[i].b = (rgb & 0x0000ff)/255. * 0.5; 00239 marker.colors[i].a = 1.0; 00240 if(marker.colors[i].g > 1.0) marker.colors[i].g = 1.0; 00241 else if(marker.colors[i].g < 0.5) marker.colors[i].g = 0.5; 00242 } 00243 } 00244 } 00245 00246 InteractiveMarkerControl control; 00247 control.always_visible = true; 00248 control.interaction_mode = InteractiveMarkerControl::MENU; 00249 control.orientation_mode = InteractiveMarkerControl::INHERIT; 00250 00251 control.markers.push_back( marker ); 00252 00253 int_marker.controls.push_back( control ); 00254 00255 marker_server_.insert( int_marker ); 00256 menu_handler_.apply( marker_server_, int_marker.name ); 00257 marker_server_.applyChanges(); 00258 } 00259 00260 00261 void GraspableObjectHandler::switchFlag( bool *value, 00262 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback ) 00263 { 00264 *value = !(bool)(*value); 00265 makeMarker(); 00266 updateMenu(); 00267 } 00268 00269 00270 }