/* * Software License Agreement (BSD License) * * Copyright (c) 2011-2014, Willow Garage, Inc. * Copyright (c) 2014-2016, Open Source Robotics Foundation * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Open Source Robotics Foundation nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ /** \author Dalibor Matura, Jia Pan */ #ifndef FCL_ARTICULATED_MODEL_MODEL_H #define FCL_ARTICULATED_MODEL_MODEL_H #include "fcl/articulated_model/joint.h" #include "fcl/articulated_model/link.h" #include "fcl/common/data_types.h" #include #include #include namespace fcl { class ModelParseError : public std::runtime_error { public: ModelParseError(const std::string& error_msg) : std::runtime_error(error_msg) {} }; template class Model { public: Model() {} virtual ~Model() {} const std::string& getName() const; void addLink(const std::shared_ptr& link); void addJoint(const std::shared_ptr& joint); void initRoot(const std::map& link_parent_tree); void initTree(std::map& link_parent_tree); std::size_t getNumDofs() const; std::size_t getNumLinks() const; std::size_t getNumJoints() const; std::shared_ptr getRoot() const; std::shared_ptr getLink(const std::string& name) const; std::shared_ptr getJoint(const std::string& name) const; std::vector > getLinks() const; std::vector > getJoints() const; protected: std::shared_ptr root_link_; std::map > links_; std::map > joints_; std::string name_; }; //============================================================================== template std::shared_ptr Model::getRoot() const { return root_link_; } //============================================================================== template std::shared_ptr Model::getLink(const std::string& name) const { std::shared_ptr ptr; std::map >::const_iterator it = links_.find(name); if(it == links_.end()) ptr.reset(); else ptr = it->second; return ptr; } //============================================================================== template std::shared_ptr Model::getJoint(const std::string& name) const { std::shared_ptr ptr; std::map >::const_iterator it = joints_.find(name); if(it == joints_.end()) ptr.reset(); else ptr = it->second; return ptr; } //============================================================================== template const std::string& Model::getName() const { return name_; } //============================================================================== template std::vector > Model::getLinks() const { std::vector > links; for(std::map >::const_iterator it = links_.begin(); it != links_.end(); ++it) { links.push_back(it->second); } return links; } //============================================================================== template std::size_t Model::getNumLinks() const { return links_.size(); } //============================================================================== template std::size_t Model::getNumJoints() const { return joints_.size(); } //============================================================================== template std::size_t Model::getNumDofs() const { std::size_t dof = 0; for(std::map >::const_iterator it = joints_.begin(); it != joints_.end(); ++it) { dof += it->second->getNumDofs(); } return dof; } //============================================================================== template void Model::addLink(const std::shared_ptr& link) { links_[link->getName()] = link; } //============================================================================== template void Model::addJoint(const std::shared_ptr& joint) { joints_[joint->getName()] = joint; } //============================================================================== template void Model::initRoot(const std::map& link_parent_tree) { root_link_.reset(); /// find the links that have no parent in the tree for(std::map >::const_iterator it = links_.begin(); it != links_.end(); ++it) { std::map::const_iterator parent = link_parent_tree.find(it->first); if(parent == link_parent_tree.end()) { if(!root_link_) { root_link_ = getLink(it->first); } else { throw ModelParseError("Two root links found: [" + root_link_->getName() + "] and [" + it->first + "]"); } } } if(!root_link_) throw ModelParseError("No root link found."); } //============================================================================== template void Model::initTree(std::map& link_parent_tree) { for(std::map >::iterator it = joints_.begin(); it != joints_.end(); ++it) { std::string parent_link_name = it->second->getParentLink()->getName(); std::string child_link_name = it->second->getChildLink()->getName(); it->second->getParentLink()->addChildJoint(it->second); it->second->getChildLink()->setParentJoint(it->second); link_parent_tree[child_link_name] = parent_link_name; } } } // namespace fcl #endif