00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2012, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 /* Author: Ioan Sucan */ 00036 00037 #include <moveit/planning_scene_monitor/planning_scene_monitor.h> 00038 00039 int main(int argc, char **argv) 00040 { 00041 ros::init(argc, argv, "display_random_state"); 00042 00043 bool valid = false; 00044 bool invalid = false; 00045 for (int i = 0 ; i < argc ; ++i) 00046 { 00047 if (strcmp(argv[i], "--valid") == 0) 00048 { 00049 valid = true; 00050 break; 00051 } 00052 if (strcmp(argv[i], "--invalid") == 0) 00053 { 00054 invalid = true; 00055 break; 00056 } 00057 } 00058 00059 ros::AsyncSpinner spinner(1); 00060 spinner.start(); 00061 00062 ros::NodeHandle nh; 00063 robot_model_loader::RobotModelLoader::Options opt; 00064 opt.robot_description_ = "robot_description"; 00065 robot_model_loader::RobotModelLoaderPtr rml(new robot_model_loader::RobotModelLoader(opt)); 00066 planning_scene_monitor::PlanningSceneMonitor psm(rml); 00067 psm.startWorldGeometryMonitor(); 00068 psm.startSceneMonitor(); 00069 ros::Publisher pub_scene = nh.advertise<moveit_msgs::PlanningScene>("planning_scene", 1); 00070 00071 ros::Duration(0.5).sleep(); 00072 00073 do 00074 { 00075 if(!psm.getPlanningScene()) 00076 { 00077 ROS_ERROR("Planning scene did not load properly, exiting..."); 00078 break; 00079 } 00080 00081 std::cout << "Type a number and hit Enter. That number of "; 00082 if (valid) 00083 std::cout << "valid "; 00084 else 00085 if (invalid) 00086 std::cout << "invalid "; 00087 std::cout << "states will be randomly generated at an interval of one second and published as a planning scene." << std::endl; 00088 std::size_t n; 00089 std::cin >> n; 00090 00091 for (std::size_t i = 0 ; i < n ; ++i) 00092 { 00093 if (valid) 00094 { 00095 bool found = false; 00096 unsigned int attempts = 0; 00097 do 00098 { 00099 attempts++; 00100 psm.getPlanningScene()->getCurrentStateNonConst().setToRandomValues(); 00101 collision_detection::CollisionRequest req; 00102 collision_detection::CollisionResult res; 00103 psm.getPlanningScene()->checkCollision(req, res); 00104 found = !res.collision; 00105 } while (!found && attempts < 100); 00106 if (!found) 00107 { 00108 std::cout << "Unable to find valid state" << std::cout; 00109 continue; 00110 } 00111 } 00112 else 00113 if (invalid) 00114 { 00115 bool found = false; 00116 unsigned int attempts = 0; 00117 do 00118 { 00119 attempts++; 00120 psm.getPlanningScene()->getCurrentStateNonConst().setToRandomValues(); 00121 collision_detection::CollisionRequest req; 00122 collision_detection::CollisionResult res; 00123 psm.getPlanningScene()->checkCollision(req, res); 00124 found = res.collision; 00125 } while (!found && attempts < 100); 00126 if (!found) 00127 { 00128 std::cout << "Unable to find invalid state" << std::cout; 00129 continue; 00130 } 00131 } 00132 else 00133 psm.getPlanningScene()->getCurrentStateNonConst().setToRandomValues(); 00134 00135 moveit_msgs::PlanningScene psmsg; 00136 psm.getPlanningScene()->getPlanningSceneMsg(psmsg); 00137 pub_scene.publish(psmsg); 00138 psm.getPlanningScene()->getCurrentState().printStateInfo(); 00139 00140 sleep(1); 00141 } 00142 } while (nh.ok()); 00143 00144 ros::shutdown(); 00145 return 0; 00146 }