00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, 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 00037 #ifndef PLANNING_ENVIRONMENT_MODELS_ROBOT_MODELS_ 00038 #define PLANNING_ENVIRONMENT_MODELS_ROBOT_MODELS_ 00039 00040 #include <planning_models/kinematic_model.h> 00041 #include <ros/ros.h> 00042 #include <boost/shared_ptr.hpp> 00043 00044 #include <map> 00045 #include <string> 00046 #include <vector> 00047 00048 namespace planning_environment 00049 { 00050 00053 class RobotModels 00054 { 00055 public: 00056 00057 struct GroupConfig 00058 { 00059 GroupConfig(std::string name) : name_(name){ 00060 } 00061 00062 ~GroupConfig() { 00063 } 00064 00065 const std::vector<std::string>& getJointNames() { 00066 return joint_names_; 00067 } 00068 const std::vector<std::string>& getLinkNames() { 00069 return link_names_; 00070 } 00071 00072 std::string name_; 00073 std::vector<std::string> joint_names_; 00074 std::vector<std::string> link_names_; 00075 }; 00076 00077 RobotModels(const std::string &description) 00078 { 00079 description_ = nh_.resolveName(description); 00080 loaded_models_ = false; 00081 loadRobot(); 00082 } 00083 00084 virtual ~RobotModels(void) 00085 { 00086 for(std::map<std::string, GroupConfig*>::iterator it = group_config_map_.begin(); 00087 it != group_config_map_.end(); 00088 it++) { 00089 delete it->second; 00090 } 00091 } 00092 00094 const std::string &getDescription(void) const 00095 { 00096 return description_; 00097 } 00098 00100 const boost::shared_ptr<planning_models::KinematicModel> &getKinematicModel(void) const 00101 { 00102 return kmodel_; 00103 } 00104 00106 const boost::shared_ptr<urdf::Model> &getParsedDescription(void) const 00107 { 00108 return urdf_; 00109 } 00110 00112 const std::map< std::string, std::vector<std::string> > &getPlanningGroupJoints(void) const 00113 { 00114 return planning_group_joints_; 00115 } 00116 00118 const std::map<std::string, std::vector<std::string> > &getPlanningGroupLinks(void) const { 00119 return planning_group_links_; 00120 } 00121 00123 const std::vector<std::string>& getGroupJointUnion(void) const { 00124 return group_joint_union_; 00125 } 00126 00128 const std::vector<std::string>& getGroupLinkUnion(void) const { 00129 return group_link_union_; 00130 } 00131 00133 bool loadedModels(void) const 00134 { 00135 return loaded_models_; 00136 } 00137 00139 virtual void reload(void); 00140 00141 protected: 00142 00143 void loadRobot(void); 00144 00145 void readGroupConfigs(); 00146 00147 bool readMultiDofConfigs(); 00148 00149 ros::NodeHandle nh_; 00150 00151 std::string description_; 00152 00153 bool loaded_models_; 00154 boost::shared_ptr<planning_models::KinematicModel> kmodel_; 00155 00156 boost::shared_ptr<urdf::Model> urdf_; 00157 00158 std::map< std::string, std::vector<std::string> > planning_group_links_; 00159 std::map< std::string, std::vector<std::string> > planning_group_joints_; 00160 std::vector<std::string> group_joint_union_; 00161 std::vector<std::string> group_link_union_; 00162 std::map< std::string, GroupConfig*> group_config_map_; 00163 std::vector<planning_models::KinematicModel::MultiDofConfig> multi_dof_configs_; 00164 00165 00166 }; 00167 00168 } 00169 00170 #endif 00171