Moby
SDFReader.h
1 /****************************************************************************
2  * Copyright 2014 Evan Drumwright
3  * This library is distributed under the terms of the Apache V2.0
4  * License (obtainable from http://www.apache.org/licenses/LICENSE-2.0).
5  ****************************************************************************/
6 
7 #ifndef _SDF_READER_H
8 #define _SDF_READER_H
9 
10 #include <Ravelin/VectorNd.h>
11 #include <Ravelin/MatrixNd.h>
12 #include <map>
13 #include <string>
14 #include <vector>
15 #include <boost/shared_ptr.hpp>
16 #include <Moby/Types.h>
17 #include <Moby/TimeSteppingSimulator.h>
18 
19 namespace Moby {
20 
21 class Simulator;
22 class RigidBody;
23 class RCArticulatedBody;
24 class MCArticulatedBody;
25 class Primitive;
26 
28 class SDFReader
29 {
30  public:
31  static boost::shared_ptr<TimeSteppingSimulator> read(const std::string& fname);
32  static std::map<std::string, ControlledBodyPtr> read_models(const std::string& fname);
33 
34  private:
35  enum TupleType { eNone, eVectorN, eVector3, eQuat };
36  static std::vector<boost::shared_ptr<Primitive> > _primitives;
37  static std::vector<boost::shared_ptr<OSGGroupWrapper> > _osg_wrappers;
38 
39  struct SurfaceData
40  {
41  double epsilon; // coefficient of restitution
42  double mu_c; // Coulomb friction coefficient
43  double mu_v; // viscous friction coefficient
44  unsigned NK; // edges in friction cone approximation
45  };
46 
47  static void read_surface(boost::shared_ptr<const XMLTree> node, boost::shared_ptr<SurfaceData>& sd);
48  static boost::shared_ptr<TimeSteppingSimulator> read_world(boost::shared_ptr<const XMLTree> node);
49  static std::vector<ControlledBodyPtr> read_models(boost::shared_ptr<const XMLTree> node, boost::shared_ptr<TimeSteppingSimulator> sim);
50  static std::string read_string(boost::shared_ptr<const XMLTree> node);
51  static unsigned read_uint(boost::shared_ptr<const XMLTree> node);
52  static double read_double(boost::shared_ptr<const XMLTree> node);
53  static bool read_bool(boost::shared_ptr<const XMLTree> node);
54  static Ravelin::Vector3d read_Vector3(boost::shared_ptr<const XMLTree> node);
55  static boost::shared_ptr<const XMLTree> find_subtree(boost::shared_ptr<const XMLTree> root, const std::string& name);
56  static boost::shared_ptr<const XMLTree> find_one_tag(const std::string& tag, boost::shared_ptr<const XMLTree> root);
57  static std::list<boost::shared_ptr<const XMLTree> > find_tag(const std::string& tag, boost::shared_ptr<const XMLTree> root);
58  static void find_tag(const std::string& tag, boost::shared_ptr<const XMLTree> root, std::list<boost::shared_ptr<const XMLTree> >& l);
59  static boost::shared_ptr<OSGGroupWrapper> read_OSG_file(boost::shared_ptr<const XMLTree> node);
60  static PrimitivePtr read_heightmap(boost::shared_ptr<const XMLTree> node);
61  static PrimitivePtr read_plane(boost::shared_ptr<const XMLTree> node);
62  static PrimitivePtr read_box(boost::shared_ptr<const XMLTree> node);
63  static PrimitivePtr read_sphere(boost::shared_ptr<const XMLTree> node);
64  static PrimitivePtr read_cylinder(boost::shared_ptr<const XMLTree> node);
65  static PrimitivePtr read_cone(boost::shared_ptr<const XMLTree> node);
66  static PrimitivePtr read_trimesh(boost::shared_ptr<const XMLTree> node);
67  static PrimitivePtr read_polyhedron(boost::shared_ptr<const XMLTree> node);
68  static ControlledBodyPtr read_model(boost::shared_ptr<const XMLTree> node, std::map<RigidBodyPtr, boost::shared_ptr<SurfaceData> >& sdata);
69  static RigidBodyPtr read_link(boost::shared_ptr<const XMLTree> node, boost::shared_ptr<SurfaceData>& sdata);
70  static void read_collision_node(boost::shared_ptr<const XMLTree> node, RigidBodyPtr rb, boost::shared_ptr<SurfaceData>& sd);
71  static void read_visual_node(boost::shared_ptr<const XMLTree> node, RigidBodyPtr rb);
72  static osg::Node* read_visual_geometry(boost::shared_ptr<const XMLTree> node);
73  static PrimitivePtr read_geometry(boost::shared_ptr<const XMLTree> node);
74  static Ravelin::Pose3d read_pose(boost::shared_ptr<const XMLTree> node);
75  static Ravelin::SpatialRBInertiad read_inertial(boost::shared_ptr<const XMLTree> node, RigidBodyPtr rb);
76 
77  static JointPtr read_joint(boost::shared_ptr<const XMLTree> node, const std::map<std::string, RigidBodyPtr>& link_map, RigidBodyPtr& base_link);
78  static TupleType get_tuple(boost::shared_ptr<const XMLTree> node);
79 }; // end class
80 } // end namespace
81 
82 #endif
83 
boost::shared_ptr< Primitive > PrimitivePtr
Primitive smart pointer.
Definition: Types.h:80
static std::map< std::string, ControlledBodyPtr > read_models(const std::string &fname)
Reads models only from SDF file.
Definition: SDFReader.cpp:172
static boost::shared_ptr< TimeSteppingSimulator > read(const std::string &fname)
Reads an XML file and constructs all read objects.
Definition: SDFReader.cpp:87
boost::shared_ptr< ControlledBody > ControlledBodyPtr
Dynamic body smart pointer.
Definition: Types.h:89
boost::shared_ptr< RigidBody > RigidBodyPtr
Rigid body smart pointer.
Definition: Types.h:62
boost::shared_ptr< Joint > JointPtr
Reduced-coordinate articulated body joint smart pointer.
Definition: Types.h:74
Used to read the simulator state from XML.
Definition: SDFReader.h:28