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 {
00049 graspable_objects_sub_ = root_nh_.subscribe("interactive_object_recognition_result", 10,
00050 &InteractiveMarkerNode::processGraspableObjects, this);
00051
00052 options_.collision_checked = true;
00053 options_.grasp_selection = 1;
00054
00055 options_.adv_options.lift_steps = 10;
00056 options_.adv_options.retreat_steps = 10;
00057 options_.adv_options.reactive_force = false;
00058 options_.adv_options.reactive_grasping = false;
00059 options_.adv_options.reactive_place = false;
00060 options_.adv_options.lift_direction_choice = 0;
00061
00062 dyn_conf_srv_.setCallback( boost::bind(&InteractiveMarkerNode::processConfig, this, _1, _2) );
00063 collision_map_interface_.resetCollisionId(1000);
00064
00065 }
00066
00067 InteractiveMarkerNode::~InteractiveMarkerNode()
00068 {
00069 }
00070
00071 void InteractiveMarkerNode::processConfig(PickupConfig &config, uint32_t level)
00072 {
00073 options_.adv_options.reactive_grasping = config.reactive_grasping;
00074 options_.adv_options.lift_steps = config.lift_steps;
00075 if (config.lift_vertically) options_.adv_options.lift_direction_choice = 0;
00076 else options_.adv_options.lift_direction_choice = 1;
00077 }
00078
00079 void InteractiveMarkerNode::processGraspableObjects(
00080 const pr2_interactive_object_detection::GraspableObjectListConstPtr &objects)
00081 {
00082 object_handlers_.clear();
00083
00084 if ( objects->meshes.size() != objects->graspable_objects.size() )
00085 {
00086 ROS_ERROR( "Number of meshes an graspable objects is not identical!" );
00087 return;
00088 }
00089
00090 for ( unsigned o=0; o<objects->meshes.size() && o<objects->graspable_objects.size(); o++ )
00091 {
00092 char name[255];
00093 sprintf( name, "object_%d", o );
00094
00095 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_ ) ) );
00096 }
00097 marker_server_.applyChanges();
00098 }
00099
00100 std::vector<object_manipulation_msgs::GraspableObject> InteractiveMarkerNode::getMovableObstacles()
00101 {
00102 std::vector<object_manipulation_msgs::GraspableObject> movable_obstacles;
00103 for (size_t i=0; i<object_handlers_.size(); i++)
00104 {
00105 if (!object_handlers_[i]->getCollisionName().empty())
00106 {
00107 movable_obstacles.push_back(object_handlers_[i]->getGraspableObject());
00108 }
00109 }
00110 return movable_obstacles;
00111 }
00112
00113 }
00114
00115
00116 int main(int argc, char **argv)
00117 {
00118 ros::init(argc, argv, "interactive_manipulation_marker_node");
00119 pr2_interactive_manipulation::InteractiveMarkerNode node;
00120 ros::spin();
00121 return 0;
00122 }
00123