link.h
Go to the documentation of this file.
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 
00035 /* Author: Wim Meeussen */
00036 
00037 #ifndef URDF_INTERFACE_LINK_H
00038 #define URDF_INTERFACE_LINK_H
00039 
00040 #include <string>
00041 #include <vector>
00042 #include <tinyxml.h>
00043 #include <boost/shared_ptr.hpp>
00044 #include <boost/weak_ptr.hpp>
00045 
00046 #include "joint.h"
00047 #include "color.h"
00048 
00049 namespace urdf{
00050 
00051 class Geometry
00052 {
00053 public:
00054   enum {SPHERE, BOX, CYLINDER, MESH} type;
00055 
00056   virtual bool initXml(TiXmlElement *) = 0;
00057 
00058 };
00059 
00060 class Sphere : public Geometry
00061 {
00062 public:
00063   Sphere() { this->clear(); };
00064   double radius;
00065 
00066   void clear()
00067   {
00068     radius = 0;
00069   };
00070   bool initXml(TiXmlElement *);
00071 };
00072 
00073 class Box : public Geometry
00074 {
00075 public:
00076   Box() { this->clear(); };
00077   Vector3 dim;
00078 
00079   void clear()
00080   {
00081     dim.clear();
00082   };
00083   bool initXml(TiXmlElement *);
00084 };
00085 
00086 class Cylinder : public Geometry
00087 {
00088 public:
00089   Cylinder() { this->clear(); };
00090   double length;
00091   double radius;
00092 
00093   void clear()
00094   {
00095     length = 0;
00096     radius = 0;
00097   };
00098   bool initXml(TiXmlElement *);
00099 };
00100 
00101 class Mesh : public Geometry
00102 {
00103 public:
00104   Mesh() { this->clear(); };
00105   std::string filename;
00106   Vector3 scale;
00107 
00108   void clear()
00109   {
00110     filename.clear();
00111     // default scale
00112     scale.x = 1;
00113     scale.y = 1;
00114     scale.z = 1;
00115   };
00116   bool initXml(TiXmlElement *);
00117   bool fileExists(std::string filename);
00118 };
00119 
00120 class Material
00121 {
00122 public:
00123   Material() { this->clear(); };
00124   std::string name;
00125   std::string texture_filename;
00126   Color color;
00127 
00128   void clear()
00129   {
00130     color.clear();
00131     texture_filename.clear();
00132     name.clear();
00133   };
00134   bool initXml(TiXmlElement* config);
00135 };
00136 
00137 class Inertial
00138 {
00139 public:
00140   Inertial() { this->clear(); };
00141   Pose origin;
00142   double mass;
00143   double ixx,ixy,ixz,iyy,iyz,izz;
00144 
00145   void clear()
00146   {
00147     origin.clear();
00148     mass = 0;
00149     ixx = ixy = ixz = iyy = iyz = izz = 0;
00150   };
00151   bool initXml(TiXmlElement* config);
00152 };
00153 
00154 class Visual
00155 {
00156 public:
00157   Visual() { this->clear(); };
00158   Pose origin;
00159   boost::shared_ptr<Geometry> geometry;
00160 
00161   std::string material_name;
00162   boost::shared_ptr<Material> material;
00163 
00164   void clear()
00165   {
00166     origin.clear();
00167     material_name.clear();
00168     material.reset();
00169     geometry.reset();
00170     this->group_name.clear();
00171   };
00172   bool initXml(TiXmlElement* config);
00173   std::string group_name;
00174 };
00175 
00176 class Collision
00177 {
00178 public:
00179   Collision() { this->clear(); };
00180   Pose origin;
00181   boost::shared_ptr<Geometry> geometry;
00182 
00183   void clear()
00184   {
00185     origin.clear();
00186     geometry.reset();
00187     this->group_name.clear();
00188   };
00189   bool initXml(TiXmlElement* config);
00190   std::string group_name;
00191 };
00192 
00193 
00194 class Link
00195 {
00196 public:
00197   Link() { this->clear(); };
00198 
00199   std::string name;
00200 
00202   boost::shared_ptr<Inertial> inertial;
00203 
00205   boost::shared_ptr<Visual> visual;
00206 
00208   boost::shared_ptr<Collision> collision;
00209 
00211   std::map<std::string, boost::shared_ptr<std::vector<boost::shared_ptr<Visual> > > > visual_groups;
00212 
00214   std::map<std::string, boost::shared_ptr<std::vector<boost::shared_ptr<Collision> > > > collision_groups;
00215 
00219   boost::shared_ptr<Joint> parent_joint;
00220 
00221   std::vector<boost::shared_ptr<Joint> > child_joints;
00222   std::vector<boost::shared_ptr<Link> > child_links;
00223 
00224   bool initXml(TiXmlElement* config);
00225 
00226   boost::shared_ptr<Link> getParent() const
00227   {return parent_link_.lock();};
00228 
00229   void setParent(boost::shared_ptr<Link> parent);
00230 
00231   void clear()
00232   {
00233     this->name.clear();
00234     this->inertial.reset();
00235     this->visual.reset();
00236     this->collision.reset();
00237     this->parent_joint.reset();
00238     this->child_joints.clear();
00239     this->child_links.clear();
00240     this->collision_groups.clear();
00241   };
00242   void setParentJoint(boost::shared_ptr<Joint> child);
00243   void addChild(boost::shared_ptr<Link> child);
00244   void addChildJoint(boost::shared_ptr<Joint> child);
00245 
00246   void addVisual(std::string group_name, boost::shared_ptr<Visual> visual);
00247   boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > > getVisuals(const std::string& group_name) const;
00248   void addCollision(std::string group_name, boost::shared_ptr<Collision> collision);
00249   boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > > getCollisions(const std::string& group_name) const;
00250 private:
00251   boost::weak_ptr<Link> parent_link_;
00252 
00253 };
00254 
00255 
00256 
00257 
00258 }
00259 
00260 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


urdf_interface
Author(s): Wim Meeussen, John Hsu
autogenerated on Mon Aug 19 2013 11:02:01