Program Listing for File model.h

Return to documentation for file (include/srdfdom/model.h)

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2011, Willow Garage, Inc.
 *  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 the Willow Garage 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 Ioan Sucan */

#ifndef SRDF_MODEL_
#define SRDF_MODEL_

#include <map>
#include <string>
#include <vector>
#include <utility>
#include <memory>
#include <tinyxml2.h>

#if __has_include(<urdf/model.hpp>)
#include <urdf/model.hpp>
#else
#include <urdf/model.h>
#endif

#include "visibility_control.h"

namespace srdf
{
class SRDFDOM_PUBLIC Model
{
public:
  Model()
  {
  }

  ~Model()
  {
  }

  bool initXml(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* xml);
  bool initXml(const urdf::ModelInterface& urdf_model, tinyxml2::XMLDocument* xml);
  bool initFile(const urdf::ModelInterface& urdf_model, const std::string& filename);
  bool initString(const urdf::ModelInterface& urdf_model, const std::string& xmlstring);

  struct Group
  {
    std::string name_;

    std::vector<std::string> joints_;

    std::vector<std::string> links_;

    std::vector<std::pair<std::string, std::string>> chains_;

    std::vector<std::string> subgroups_;
  };

  struct VirtualJoint
  {
    std::string name_;

    std::string type_;

    std::string parent_frame_;

    std::string child_link_;
  };

  struct EndEffector
  {
    std::string name_;

    std::string parent_link_;

    std::string parent_group_;

    std::string component_group_;
  };

  struct GroupState
  {
    std::string name_;

    std::string group_;

    std::map<std::string, std::vector<double>> joint_values_;
  };

  struct Sphere
  {
    double center_x_;
    double center_y_;
    double center_z_;

    double radius_;
  };

  struct LinkSpheres
  {
    std::string link_;

    std::vector<Sphere> spheres_;
  };

  struct CollisionPair
  {
    std::string link1_;

    std::string link2_;

    std::string reason_;
  };

  // Some joints can be passive (not actuated). This structure specifies information about such joints
  struct PassiveJoint
  {
    std::string name_;
  };

  // Some joints may have additional properties.
  struct JointProperty
  {
    std::string joint_name_;

    std::string property_name_;

    std::string value_;
  };

  const std::string& getName() const
  {
    return name_;
  }

  const std::vector<std::string>& getNoDefaultCollisionLinks() const
  {
    return no_default_collision_links_;
  }

  const std::vector<CollisionPair>& getEnabledCollisionPairs() const
  {
    return enabled_collision_pairs_;
  }

  const std::vector<CollisionPair>& getDisabledCollisionPairs() const
  {
    return disabled_collision_pairs_;
  }

  const std::vector<Group>& getGroups() const
  {
    return groups_;
  }

  const std::vector<VirtualJoint>& getVirtualJoints() const
  {
    return virtual_joints_;
  }

  const std::vector<EndEffector>& getEndEffectors() const
  {
    return end_effectors_;
  }

  const std::vector<GroupState>& getGroupStates() const
  {
    return group_states_;
  }

  const std::vector<PassiveJoint>& getPassiveJoints() const
  {
    return passive_joints_;
  }

  const std::vector<LinkSpheres>& getLinkSphereApproximations() const
  {
    return link_sphere_approximations_;
  }

  const std::vector<JointProperty>& getJointProperties(const std::string& joint_name) const
  {
    std::map<std::string, std::vector<JointProperty>>::const_iterator iter = joint_properties_.find(joint_name);
    if (iter == joint_properties_.end())
    {
      // We return a standard empty vector here rather than insert a new empty vector
      // into the map in order to keep the method const
      return empty_vector_;
    }
    return iter->second;
  }

  const std::map<std::string, std::vector<JointProperty>>& getJointProperties() const
  {
    return joint_properties_;
  }

  void clear();

private:
  bool isValidJoint(const urdf::ModelInterface& urdf_model, const std::string& name) const;

  void loadVirtualJoints(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
  void loadGroups(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
  void loadGroupStates(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
  void loadEndEffectors(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
  void loadLinkSphereApproximations(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
  void loadCollisionDefaults(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
  void loadCollisionPairs(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml, const char* tag_name,
                          std::vector<CollisionPair>& pairs);
  void loadPassiveJoints(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
  void loadJointProperties(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);

  std::string name_;
  std::vector<Group> groups_;
  std::vector<GroupState> group_states_;
  std::vector<VirtualJoint> virtual_joints_;
  std::vector<EndEffector> end_effectors_;
  std::vector<LinkSpheres> link_sphere_approximations_;
  std::vector<std::string> no_default_collision_links_;
  std::vector<CollisionPair> enabled_collision_pairs_;
  std::vector<CollisionPair> disabled_collision_pairs_;
  std::vector<PassiveJoint> passive_joints_;
  std::map<std::string, std::vector<JointProperty>> joint_properties_;

  // Empty joint property vector
  static const std::vector<JointProperty> empty_vector_;
};
typedef std::shared_ptr<Model> ModelSharedPtr;
typedef std::shared_ptr<const Model> ModelConstSharedPtr;
}  // namespace srdf
#endif