model.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2011, 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 #ifndef SRDF_MODEL_
00038 #define SRDF_MODEL_
00039 
00040 #include <map>
00041 #include <string>
00042 #include <vector>
00043 #include <utility>
00044 #include <urdf_interface/model.h>
00045 #include <tinyxml.h>
00046 
00048 namespace srdf
00049 {
00050 
00052 class Model
00053 {
00054 public:
00055   
00056   Model(void)
00057   {
00058   }
00059   
00060   ~Model(void)
00061   {
00062   }
00063   
00065   bool initXml(const urdf::ModelInterface &urdf_model, TiXmlElement *xml);
00067   bool initXml(const urdf::ModelInterface &urdf_model, TiXmlDocument *xml);
00069   bool initFile(const urdf::ModelInterface &urdf_model, const std::string& filename);
00071   bool initString(const urdf::ModelInterface &urdf_model, const std::string& xmlstring);
00072   
00077   struct Group
00078   {
00080     std::string                                       name_;
00081     
00087     std::vector<std::string>                          joints_;
00088     
00093     std::vector<std::string>                          links_;
00094     
00099     std::vector<std::pair<std::string, std::string> > chains_;
00100     
00104     std::vector<std::string>                          subgroups_;
00105   };
00106   
00111   struct VirtualJoint
00112   {
00114     std::string name_;
00115     
00117     std::string type_;
00118     
00120     std::string parent_frame_;
00121     
00123     std::string child_link_;
00124   };
00125   
00127   struct EndEffector
00128   {
00130     std::string name_;
00131     
00133     std::string parent_link_;
00134     
00136     std::string component_group_;
00137   };
00138   
00140   struct GroupState
00141   {
00143     std::string                                 name_;
00144     
00146     std::string                                 group_;
00147     
00149     std::map<std::string, std::vector<double> > joint_values_;
00150   };
00151   
00153   const std::string& getName(void) const
00154   {
00155     return name_;
00156   }
00157   
00159   const std::vector<std::pair<std::string, std::string> >& getDisabledCollisions(void) const
00160   {
00161     return disabled_collisions_;
00162   }
00163   
00165   const std::vector<Group>& getGroups(void) const
00166   {
00167     return groups_;
00168   }
00169   
00171   const std::vector<VirtualJoint>& getVirtualJoints(void) const
00172   {
00173     return virtual_joints_;
00174   }
00175   
00177   const std::vector<EndEffector>& getEndEffectors(void) const
00178   {
00179     return end_effectors_;
00180   }
00181   
00183   const std::vector<GroupState>& getGroupStates(void) const
00184   {
00185     return group_states_;
00186   }
00187   
00189   void clear(void);
00190   
00191 private:
00192   
00193   void loadVirtualJoints(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
00194   void loadGroups(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
00195   void loadGroupStates(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
00196   void loadEndEffectors(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
00197   void loadDisabledCollisions(const urdf::ModelInterface &urdf_model, TiXmlElement *robot_xml);
00198   
00199   std::string                                       name_;
00200   std::vector<Group>                                groups_;
00201   std::vector<GroupState>                           group_states_;
00202   std::vector<VirtualJoint>                         virtual_joints_;
00203   std::vector<EndEffector>                          end_effectors_;
00204   std::vector<std::pair<std::string, std::string> > disabled_collisions_;
00205 };
00206 
00207 }
00208 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


srdf
Author(s): Ioan Sucan
autogenerated on Mon Aug 19 2013 11:02:22