Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 #include "pr2_interactive_manipulation/interactive_marker_node.h"
00031 
00032 #include <visualization_msgs/InteractiveMarker.h>
00033 #include <visualization_msgs/InteractiveMarkerFeedback.h>
00034 
00035 using namespace visualization_msgs;
00036 using namespace interactive_markers;
00037 
00038 namespace pr2_interactive_manipulation
00039 {
00040 
00041 typedef actionlib::SimpleActionClient<pr2_object_manipulation_msgs::IMGUIAction> IMGUIActionClient;
00042 
00043 InteractiveMarkerNode::InteractiveMarkerNode() :
00044   root_nh_(""),
00045   priv_nh_("~"),
00046   im_gui_action_client_("imgui_action", true),
00047   marker_server_("interactive_manipulation"),
00048   pickup_as_(root_nh_, "pickup_im_object_action", boost::bind(&InteractiveMarkerNode::pickupIMObject, this, _1), false)
00049 {
00050   graspable_objects_sub_ = root_nh_.subscribe("interactive_object_recognition_result", 10,
00051     &InteractiveMarkerNode::processGraspableObjects, this);
00052 
00053   options_.collision_checked = true;
00054   options_.grasp_selection = 1;
00055 
00056   options_.adv_options.lift_steps = 10;
00057   options_.adv_options.retreat_steps = 10;
00058   options_.adv_options.reactive_force = false;
00059   options_.adv_options.reactive_grasping = false;
00060   options_.adv_options.reactive_place = false;
00061   options_.adv_options.lift_direction_choice = 0;
00062 
00063   dyn_conf_srv_.setCallback( boost::bind(&InteractiveMarkerNode::processConfig, this, _1, _2) );
00064   collision_map_interface_.resetCollisionId(1000);
00065 
00066   pickup_as_.start();
00067 
00068   ROS_INFO("interactive_marker_node: done init");
00069 }
00070 
00071 InteractiveMarkerNode::~InteractiveMarkerNode()
00072 {
00073 }
00074 
00075 void InteractiveMarkerNode::pickupIMObject(const pr2_object_manipulation_msgs::PickupIMObjectGoalConstPtr &goal)
00076 {
00077   ROS_INFO("interactive_marker_node: picking up object number %d", goal->object_id);
00078 
00079   if(goal->object_id >= (int)object_handlers_.size())
00080   {
00081     ROS_ERROR("interactive_marker_node: object_id %d doesn't exist!", goal->object_id);    
00082     pickup_as_.setAborted();
00083     return;
00084   }
00085 
00086   object_handlers_[goal->object_id]->callPickup(goal->arm_selection);
00087 
00088   pickup_as_.setSucceeded();
00089 
00090 }
00091 
00092 void InteractiveMarkerNode::processConfig(PickupConfig &config, uint32_t level)
00093 {
00094   options_.adv_options.reactive_grasping = config.reactive_grasping;
00095   options_.adv_options.lift_steps = config.lift_steps;
00096   if (config.lift_vertically) options_.adv_options.lift_direction_choice = 0;
00097   else options_.adv_options.lift_direction_choice = 1;
00098 }
00099 
00100 void InteractiveMarkerNode::processGraspableObjects(
00101                                           const manipulation_msgs::GraspableObjectListConstPtr &objects)
00102 {
00103   object_handlers_.clear();
00104 
00105   if ( objects->meshes.size() != objects->graspable_objects.size() )
00106   {
00107     ROS_ERROR( "Number of meshes an graspable objects is not identical!" );
00108     return;
00109   }
00110 
00111   for ( unsigned o=0; o<objects->meshes.size() && o<objects->graspable_objects.size(); o++ )
00112   {
00113     char name[255];
00114     sprintf( name, "object_%d", o );
00115 
00116     object_handlers_.push_back( boost::shared_ptr<GraspableObjectHandler>( new GraspableObjectHandler( name, this, objects->graspable_objects[o], objects->meshes[o], marker_server_, options_, &collision_map_interface_ ) ) );
00117   }
00118   marker_server_.applyChanges();
00119 }
00120 
00121 std::vector<manipulation_msgs::GraspableObject> InteractiveMarkerNode::getMovableObstacles()
00122 {
00123   std::vector<manipulation_msgs::GraspableObject> movable_obstacles;
00124   for (size_t i=0; i<object_handlers_.size(); i++)
00125   {
00126     if (!object_handlers_[i]->getCollisionName().empty())
00127     {
00128       movable_obstacles.push_back(object_handlers_[i]->getGraspableObject());
00129     }    
00130   }
00131   return movable_obstacles;
00132 }
00133 
00134 }
00135 
00136 
00137 int main(int argc, char **argv)
00138 {
00139   ros::init(argc, argv, "interactive_manipulation_marker_node");
00140   pr2_interactive_manipulation::InteractiveMarkerNode node;
00141   ros::spin();
00142   return 0;
00143 }
00144