Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #ifndef FCL_ARTICULATED_MODEL_MODEL_H
00038 #define FCL_ARTICULATED_MODEL_MODEL_H
00039
00040 #include "fcl/articulated_model/joint.h"
00041 #include "fcl/articulated_model/link.h"
00042
00043 #include "fcl/data_types.h"
00044 #include <boost/shared_ptr.hpp>
00045
00046 #include <map>
00047 #include <stdexcept>
00048 namespace fcl
00049 {
00050
00051 class ModelParseError : public std::runtime_error
00052 {
00053 public:
00054 ModelParseError(const std::string& error_msg) : std::runtime_error(error_msg) {}
00055 };
00056
00057 class Model
00058 {
00059 public:
00060 Model() {}
00061
00062 virtual ~Model() {}
00063
00064 const std::string& getName() const;
00065
00066 void addLink(const boost::shared_ptr<Link>& link);
00067
00068 void addJoint(const boost::shared_ptr<Joint>& joint);
00069
00070 void initRoot(const std::map<std::string, std::string>& link_parent_tree);
00071
00072 void initTree(std::map<std::string, std::string>& link_parent_tree);
00073
00074 std::size_t getNumDofs() const;
00075
00076 std::size_t getNumLinks() const;
00077
00078 std::size_t getNumJoints() const;
00079
00080 boost::shared_ptr<Link> getRoot() const;
00081 boost::shared_ptr<Link> getLink(const std::string& name) const;
00082 boost::shared_ptr<Joint> getJoint(const std::string& name) const;
00083
00084 std::vector<boost::shared_ptr<Link> > getLinks() const;
00085 std::vector<boost::shared_ptr<Joint> > getJoints() const;
00086 protected:
00087 boost::shared_ptr<Link> root_link_;
00088 std::map<std::string, boost::shared_ptr<Link> > links_;
00089 std::map<std::string, boost::shared_ptr<Joint> > joints_;
00090
00091 std::string name_;
00092
00093 };
00094
00095 }
00096
00097 #endif
00098