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 #include "fcl/articulated_model/model.h"
00038 #include "fcl/articulated_model/model_config.h"
00039 #include <boost/assert.hpp>
00040
00041 namespace fcl
00042 {
00043
00044
00045 boost::shared_ptr<Link> Model::getRoot() const
00046 {
00047 return root_link_;
00048 }
00049
00050 boost::shared_ptr<Link> Model::getLink(const std::string& name) const
00051 {
00052 boost::shared_ptr<Link> ptr;
00053 std::map<std::string, boost::shared_ptr<Link> >::const_iterator it = links_.find(name);
00054 if(it == links_.end())
00055 ptr.reset();
00056 else
00057 ptr = it->second;
00058 return ptr;
00059 }
00060
00061 boost::shared_ptr<Joint> Model::getJoint(const std::string& name) const
00062 {
00063 boost::shared_ptr<Joint> ptr;
00064 std::map<std::string, boost::shared_ptr<Joint> >::const_iterator it = joints_.find(name);
00065 if(it == joints_.end())
00066 ptr.reset();
00067 else
00068 ptr = it->second;
00069 return ptr;
00070 }
00071
00072 const std::string& Model::getName() const
00073 {
00074 return name_;
00075 }
00076
00077 std::vector<boost::shared_ptr<Link> > Model::getLinks() const
00078 {
00079 std::vector<boost::shared_ptr<Link> > links;
00080 for(std::map<std::string, boost::shared_ptr<Link> >::const_iterator it = links_.begin(); it != links_.end(); ++it)
00081 {
00082 links.push_back(it->second);
00083 }
00084
00085 return links;
00086 }
00087
00088 std::size_t Model::getNumLinks() const
00089 {
00090 return links_.size();
00091 }
00092
00093 std::size_t Model::getNumJoints() const
00094 {
00095 return joints_.size();
00096 }
00097
00098 std::size_t Model::getNumDofs() const
00099 {
00100 std::size_t dof = 0;
00101 for(std::map<std::string, boost::shared_ptr<Joint> >::const_iterator it = joints_.begin(); it != joints_.end(); ++it)
00102 {
00103 dof += it->second->getNumDofs();
00104 }
00105
00106 return dof;
00107 }
00108
00109 void Model::addLink(const boost::shared_ptr<Link>& link)
00110 {
00111 links_[link->getName()] = link;
00112 }
00113
00114 void Model::addJoint(const boost::shared_ptr<Joint>& joint)
00115 {
00116 joints_[joint->getName()] = joint;
00117 }
00118
00119 void Model::initRoot(const std::map<std::string, std::string>& link_parent_tree)
00120 {
00121 root_link_.reset();
00122
00124 for(std::map<std::string, boost::shared_ptr<Link> >::const_iterator it = links_.begin(); it != links_.end(); ++it)
00125 {
00126 std::map<std::string, std::string>::const_iterator parent = link_parent_tree.find(it->first);
00127 if(parent == link_parent_tree.end())
00128 {
00129 if(!root_link_)
00130 {
00131 root_link_ = getLink(it->first);
00132 }
00133 else
00134 {
00135 throw ModelParseError("Two root links found: [" + root_link_->getName() + "] and [" + it->first + "]");
00136 }
00137 }
00138 }
00139
00140 if(!root_link_)
00141 throw ModelParseError("No root link found.");
00142 }
00143
00144 void Model::initTree(std::map<std::string, std::string>& link_parent_tree)
00145 {
00146 for(std::map<std::string, boost::shared_ptr<Joint> >::iterator it = joints_.begin(); it != joints_.end(); ++it)
00147 {
00148 std::string parent_link_name = it->second->getParentLink()->getName();
00149 std::string child_link_name = it->second->getChildLink()->getName();
00150
00151 it->second->getParentLink()->addChildJoint(it->second);
00152 it->second->getChildLink()->setParentJoint(it->second);
00153
00154 link_parent_tree[child_link_name] = parent_link_name;
00155 }
00156 }
00157
00158 }