graspable_object_handler.cpp
Go to the documentation of this file.
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 manipulation_msgs::GraspableObject &object,
00046       const shape_msgs::Mesh &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     // pick up
00144     ROS_INFO_STREAM( "Picking up object # " << feedback->marker_name );
00145 
00146     // determine arm selection
00147     MenuHandler::EntryHandle arm_h = feedback->menu_entry_id;
00148     if ( arm_h == left_pickup_h_ ) callPickup(1);
00149     else if ( arm_h == right_pickup_h_ ) callPickup(0);
00150   }
00151 
00152   //arm_selection: 0=right, 1=left
00153   void GraspableObjectHandler::callPickup(int arm_selection)
00154   {
00155     options_.arm_selection = arm_selection;
00156     manipulation_msgs::GraspableObject object = object_;
00157 
00158     if ( !use_rec_result_ )
00159     {
00160       object.potential_models.clear();
00161     }
00162 
00163     pr2_object_manipulation_msgs::IMGUIGoal goal;
00164     goal.options = options_;
00165     goal.options.grasp_selection = 1;
00166     goal.options.selected_object = object;
00167     goal.options.movable_obstacles = interactive_marker_node_->getMovableObstacles();
00168     goal.command.command = goal.command.PICKUP;
00169 
00170     im_gui_action_client_.sendGoal(goal);
00171 
00172     marker_server_.clear();
00173     marker_server_.applyChanges();
00174   }
00175 
00176 
00177   void GraspableObjectHandler::makeMarker()
00178   {
00179     InteractiveMarker int_marker;
00180     int_marker.name = name_;
00181 
00182     Marker marker;
00183     marker.color.r = 0.0;
00184     marker.color.g = 1.0;
00185     marker.color.b = 0.0;
00186     marker.color.a = 0.5;
00187     marker.frame_locked = false;
00188 
00189     if ( use_rec_result_ && mesh_.vertices.size() > 0 )
00190     {
00191       int_marker.pose = object_.potential_models[0].pose.pose;
00192       int_marker.header = object_.potential_models[0].pose.header;
00193 
00194       marker.type = Marker::TRIANGLE_LIST;
00195 
00196       ROS_INFO_STREAM( "Adding mesh. #triangles=" << mesh_.triangles.size() );
00197 
00198       marker.points.reserve( mesh_.triangles.size()*3 );
00199 
00200       for ( size_t t=0; t<mesh_.triangles.size(); t++ )
00201       {
00202         if ( (size_t)mesh_.triangles[t].vertex_indices[0] < mesh_.vertices.size() &&
00203              (size_t)mesh_.triangles[t].vertex_indices[1] < mesh_.vertices.size() &&
00204              (size_t)mesh_.triangles[t].vertex_indices[2] < mesh_.vertices.size() )
00205         {
00206           marker.points.push_back( mesh_.vertices[ mesh_.triangles[t].vertex_indices[0] ] );
00207           marker.points.push_back( mesh_.vertices[ mesh_.triangles[t].vertex_indices[1] ] );
00208           marker.points.push_back( mesh_.vertices[ mesh_.triangles[t].vertex_indices[2] ] );
00209         }
00210         else
00211         {
00212           ROS_ERROR("Mesh contains invalid triangle!");
00213           break;
00214         }
00215       }
00216     }
00217     else
00218     {
00219       int_marker.header = object_.cluster.header;
00220       marker.scale.x = 0.01;
00221       marker.scale.y = 0.01;
00222       marker.scale.z = 0.01;
00223       marker.type = Marker::CUBE_LIST;
00224 
00225       marker.points.resize( object_.cluster.points.size() );
00226       marker.colors.resize( object_.cluster.points.size() );
00227 
00228       ROS_INFO_STREAM( "Adding point cluster. #points=" << object_.cluster.points.size() );
00229       bool use_color = false;
00230       if(object_.cluster.channels.size() != 0 && object_.cluster.channels[0].name == "rgb") use_color = true;
00231       for ( size_t i=0; i<object_.cluster.points.size(); i++)
00232       {
00233         marker.points[i].x = object_.cluster.points[i].x;
00234         marker.points[i].y = object_.cluster.points[i].y;
00235         marker.points[i].z = object_.cluster.points[i].z;
00236         if(use_color)
00237         {
00238           uint32_t rgb = *reinterpret_cast<int*>(&object_.cluster.channels[0].values[i]);
00239           marker.colors[i].r = ((rgb >> 16) & 0x0000ff)/255. * 0.5;
00240           marker.colors[i].g = ((rgb >> 8) & 0x0000ff)/255. * 1.5;
00241           marker.colors[i].b = (rgb & 0x0000ff)/255. * 0.5;
00242           marker.colors[i].a = 1.0;
00243           if(marker.colors[i].g > 1.0) marker.colors[i].g = 1.0;
00244           else if(marker.colors[i].g < 0.5) marker.colors[i].g = 0.5;
00245         }
00246       }
00247     }
00248 
00249     InteractiveMarkerControl control;
00250     control.always_visible = true;
00251     control.interaction_mode = InteractiveMarkerControl::MENU;
00252     control.orientation_mode = InteractiveMarkerControl::INHERIT;
00253 
00254     control.markers.push_back( marker );
00255 
00256     int_marker.controls.push_back( control );
00257 
00258     marker_server_.insert( int_marker );
00259     menu_handler_.apply( marker_server_, int_marker.name );
00260     marker_server_.applyChanges();
00261   }
00262 
00263 
00264   void GraspableObjectHandler::switchFlag( bool *value, 
00265       const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
00266   {
00267     *value = !(bool)(*value);
00268     makeMarker();
00269     updateMenu();
00270   }
00271 
00272 
00273 }


pr2_interactive_manipulation
Author(s): Matei Ciocarlie, Kaijen Hsiao, Adam Leeper
autogenerated on Mon Oct 6 2014 12:55:34