planning_scene_interface.cpp
Go to the documentation of this file.
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_interface/planning_scene_interface.h>
00038 #include <moveit/move_group/capability_names.h>
00039 #include <moveit_msgs/GetPlanningScene.h>
00040 #include <ros/ros.h>
00041 
00042 namespace moveit
00043 {
00044 namespace planning_interface
00045 {
00046 
00047 class PlanningSceneInterface::PlanningSceneInterfaceImpl
00048 {
00049 public:
00050 
00051   PlanningSceneInterfaceImpl()
00052   {
00053     planning_scene_service_ = node_handle_.serviceClient<moveit_msgs::GetPlanningScene>(move_group::GET_PLANNING_SCENE_SERVICE_NAME);
00054   }
00055 
00056   std::vector<std::string> getKnownObjectNames(bool with_type)
00057   {
00058     moveit_msgs::GetPlanningScene::Request request;
00059     moveit_msgs::GetPlanningScene::Response response;
00060     std::vector<std::string> result;
00061     request.components.components = request.components.WORLD_OBJECT_NAMES;
00062     if (!planning_scene_service_.call(request, response))
00063       return result;
00064     if (with_type)
00065     {
00066       for (std::size_t i = 0 ; i < response.scene.world.collision_objects.size() ; ++i)
00067         if (!response.scene.world.collision_objects[i].type.key.empty())
00068           result.push_back(response.scene.world.collision_objects[i].id);
00069     }
00070     else
00071     {
00072       for (std::size_t i = 0 ; i < response.scene.world.collision_objects.size() ; ++i)
00073         result.push_back(response.scene.world.collision_objects[i].id);
00074     }
00075     return result;
00076   }
00077 
00078   std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type)
00079   {
00080     moveit_msgs::GetPlanningScene::Request request;
00081     moveit_msgs::GetPlanningScene::Response response;
00082     std::vector<std::string> result;
00083     request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
00084     if (!planning_scene_service_.call(request, response))
00085       return result;
00086     for (std::size_t i = 0; i < response.scene.world.collision_objects.size() ; ++i)
00087     {
00088       if (with_type && !response.scene.world.collision_objects[i].type.key.empty())
00089         continue;
00090       if (response.scene.world.collision_objects[i].mesh_poses.empty() &&
00091           response.scene.world.collision_objects[i].primitive_poses.empty())
00092         continue;
00093       bool good = true;
00094       for (std::size_t j = 0 ; j < response.scene.world.collision_objects[i].mesh_poses.size() ; ++j)
00095         if (!(response.scene.world.collision_objects[i].mesh_poses[j].position.x >= minx &&
00096               response.scene.world.collision_objects[i].mesh_poses[j].position.x <= maxx &&
00097               response.scene.world.collision_objects[i].mesh_poses[j].position.y >= miny &&
00098               response.scene.world.collision_objects[i].mesh_poses[j].position.y <= maxy &&
00099               response.scene.world.collision_objects[i].mesh_poses[j].position.z >= minz &&
00100               response.scene.world.collision_objects[i].mesh_poses[j].position.z <= maxz))
00101         {
00102           good = false;
00103           break;
00104         }
00105       for (std::size_t j = 0 ; j < response.scene.world.collision_objects[i].primitive_poses.size() ; ++j)
00106         if (!(response.scene.world.collision_objects[i].primitive_poses[j].position.x >= minx &&
00107               response.scene.world.collision_objects[i].primitive_poses[j].position.x <= maxx &&
00108               response.scene.world.collision_objects[i].primitive_poses[j].position.y >= miny &&
00109               response.scene.world.collision_objects[i].primitive_poses[j].position.y <= maxy &&
00110               response.scene.world.collision_objects[i].primitive_poses[j].position.z >= minz &&
00111               response.scene.world.collision_objects[i].primitive_poses[j].position.z <= maxz))
00112         {
00113           good = false;
00114           break;
00115         }
00116       if (good)
00117         result.push_back(response.scene.world.collision_objects[i].id);
00118     }
00119     return result;
00120   }
00121 
00122 private:
00123 
00124   ros::NodeHandle node_handle_;
00125   ros::ServiceClient planning_scene_service_;
00126   robot_model::RobotModelConstPtr robot_model_;
00127 };
00128 
00129 PlanningSceneInterface::PlanningSceneInterface()
00130 {
00131   impl_ = new PlanningSceneInterfaceImpl();
00132 }
00133 
00134 PlanningSceneInterface::~PlanningSceneInterface()
00135 {
00136   delete impl_;
00137 }
00138 
00139 std::vector<std::string> PlanningSceneInterface::getKnownObjectNames(bool with_type)
00140 {
00141   return impl_->getKnownObjectNames(with_type);
00142 }
00143 
00144 std::vector<std::string> PlanningSceneInterface::getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type)
00145 {
00146   return impl_->getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type);
00147 }
00148 
00149 
00150 }
00151 }


planning_interface
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:33:28