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 
00031 
00032 
00033 
00034 
00037 #include <ros/ros.h>
00038 #include <planning_environment/monitors/planning_monitor.h>
00039 #include <collision_proximity/collision_proximity_space.h>
00040 #include <arm_navigation_msgs/GetPlanningScene.h>
00041 #include <arm_navigation_msgs/GetRobotState.h>
00042 #include <planning_environment/models/model_utils.h>
00043 
00044 static const std::string planning_scene_name = "/environment_server/get_planning_scene";      
00045 static const std::string robot_state_name = "/environment_server/get_robot_state";      
00046 
00047 int main(int argc, char** argv)
00048 {
00049   ros::init(argc, argv, "collision_proximity_test");
00050  
00051   ros::NodeHandle nh;
00052   
00053   std::string robot_description_name = nh.resolveName("robot_description", true);
00054 
00055   ros::WallTime n1 = ros::WallTime::now();
00056   collision_proximity::CollisionProximitySpace* cps = new collision_proximity::CollisionProximitySpace(robot_description_name);
00057   ros::WallTime n2 = ros::WallTime::now();
00058 
00059   ROS_INFO_STREAM("Creation took " << (n2-n1).toSec());
00060 
00061   ros::ServiceClient planning_scene_client = nh.serviceClient<arm_navigation_msgs::GetPlanningScene>(planning_scene_name, true);      
00062   ros::service::waitForService(planning_scene_name);
00063 
00064   ros::ServiceClient robot_state_service = nh.serviceClient<arm_navigation_msgs::GetRobotState>(robot_state_name, true);      
00065   ros::service::waitForService(robot_state_name);
00066 
00067   arm_navigation_msgs::GetRobotState::Request rob_state_req;
00068   arm_navigation_msgs::GetRobotState::Response rob_state_res;
00069 
00070   arm_navigation_msgs::GetPlanningScene::Request req;
00071   arm_navigation_msgs::GetPlanningScene::Response res;
00072 
00073   arm_navigation_msgs::CollisionObject obj1;
00074   obj1.header.stamp = ros::Time::now();
00075   obj1.header.frame_id = "odom_combined";
00076   obj1.id = "obj1";
00077   obj1.operation.operation = arm_navigation_msgs::CollisionObjectOperation::ADD;
00078   obj1.shapes.resize(1);
00079   obj1.shapes[0].type = arm_navigation_msgs::Shape::BOX;
00080   obj1.shapes[0].dimensions.resize(3);
00081   obj1.shapes[0].dimensions[0] = .1;
00082   obj1.shapes[0].dimensions[1] = .1;
00083   obj1.shapes[0].dimensions[2] = .75;
00084   obj1.poses.resize(1);
00085   obj1.poses[0].position.x = .6;
00086   obj1.poses[0].position.y = -.6;
00087   obj1.poses[0].position.z = .375;
00088   obj1.poses[0].orientation.w = 1.0;
00089 
00090   arm_navigation_msgs::AttachedCollisionObject att_obj;
00091   att_obj.object = obj1;
00092   att_obj.object.header.stamp = ros::Time::now();
00093   att_obj.object.header.frame_id = "r_gripper_palm_link";
00094   att_obj.link_name = "r_gripper_palm_link";
00095   att_obj.touch_links.push_back("r_gripper_palm_link");
00096   att_obj.touch_links.push_back("r_gripper_r_finger_link");
00097   att_obj.touch_links.push_back("r_gripper_l_finger_link");
00098   att_obj.touch_links.push_back("r_gripper_r_finger_tip_link");
00099   att_obj.touch_links.push_back("r_gripper_l_finger_tip_link");
00100   att_obj.touch_links.push_back("r_wrist_roll_link");
00101   att_obj.touch_links.push_back("r_wrist_flex_link");
00102   att_obj.touch_links.push_back("r_forearm_link");
00103   att_obj.touch_links.push_back("r_gripper_motor_accelerometer_link");
00104   att_obj.object.id = "obj2";
00105   att_obj.object.shapes[0].type = arm_navigation_msgs::Shape::CYLINDER;
00106   att_obj.object.shapes[0].dimensions.resize(2);
00107   att_obj.object.shapes[0].dimensions[0] = .025;
00108   att_obj.object.shapes[0].dimensions[1] = .5;
00109   att_obj.object.poses.resize(1);
00110   att_obj.object.poses[0].position.x = .12;
00111   att_obj.object.poses[0].position.y = 0.0;
00112   att_obj.object.poses[0].position.z = 0.0;
00113   att_obj.object.poses[0].orientation.w = 1.0;
00114 
00115   req.collision_object_diffs.push_back(obj1);
00116   req.attached_collision_object_diffs.push_back(att_obj);
00117 
00118   n1 = ros::WallTime::now();
00119   planning_scene_client.call(req,res);
00120   n2 = ros::WallTime::now();
00121 
00122   ROS_INFO_STREAM("Service call took " << (n2-n1).toSec());
00123   
00124   n1 = ros::WallTime::now();
00125   planning_models::KinematicState* state = cps->setupForGroupQueries("right_arm",
00126                                                                      res.complete_robot_state,
00127                                                                      res.allowed_collision_matrix,
00128                                                                      res.transformed_allowed_contacts,
00129                                                                      res.all_link_padding,
00130                                                                      res.all_collision_objects,
00131                                                                      res.all_attached_collision_objects,
00132                                                                      res.unmasked_collision_map);
00133   n2 = ros::WallTime::now();
00134   ROS_INFO_STREAM("Setup took "  << (n2-n1).toSec());
00135 
00136   ros::Rate r(10.0);
00137   std::vector<double> link_distances;
00138   std::vector<std::vector<double> > distances;
00139   std::vector<std::vector<tf::Vector3> > gradients;
00140   std::vector<std::string> link_names;
00141   std::vector<std::string> attached_body_names;
00142   std::vector<collision_proximity::CollisionType> collisions;
00143 
00144   cps->visualizeDistanceField();
00145   
00146   while(nh.ok()) {
00147     
00148     n1 = ros::WallTime::now();
00149     robot_state_service.call(rob_state_req,rob_state_res);
00150     n2 = ros::WallTime::now();
00151     
00152 
00153     planning_environment::setRobotStateAndComputeTransforms(rob_state_res.robot_state, *state);
00154 
00155     cps->setCurrentGroupState(*state);
00156     bool in_collision; 
00157     cps->getStateCollisions(link_names, attached_body_names, in_collision, collisions);
00158     cps->visualizeCollisions(link_names, attached_body_names, collisions);
00159     cps->getStateGradients(link_names, attached_body_names, link_distances, distances, gradients);
00160     cps->visualizeProximityGradients(link_names, attached_body_names, link_distances, distances, gradients);
00161     std::vector<std::string> objs = link_names;
00162     objs.insert(objs.end(), attached_body_names.begin(), attached_body_names.end());
00163     cps->visualizeObjectSpheres(objs);
00164     
00165     
00166     
00167     
00168     ros::spinOnce();
00169     r.sleep();
00170   }
00171 
00172   ros::shutdown();
00173   delete cps;
00174 
00175 }