moveit_config_data.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Dave Coleman */
00036 
00037 #ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_MOVEIT_CONFIG_DATA_
00038 #define MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_MOVEIT_CONFIG_DATA_
00039 
00040 #include <boost/shared_ptr.hpp>
00041 #include <srdfdom/model.h>        // use their struct datastructures
00042 #include <srdfdom/srdf_writer.h>  // for writing srdf data
00043 #include <urdf/model.h>           // to share throughout app
00044 #include <moveit/macros/class_forward.h>
00045 #include <moveit/planning_scene/planning_scene.h>                     // for getting kinematic model
00046 #include <moveit/collision_detection/collision_matrix.h>              // for figuring out if robot is in collision
00047 #include <moveit/setup_assistant/tools/compute_default_collisions.h>  // for LinkPairMap
00048 
00049 namespace moveit_setup_assistant
00050 {
00051 // ******************************************************************************************
00052 // Constants
00053 // ******************************************************************************************
00054 
00055 // Used for loading kinematic model
00056 static const std::string ROBOT_DESCRIPTION = "robot_description";
00057 static const std::string MOVEIT_ROBOT_STATE = "moveit_robot_state";
00058 
00059 // Default kin solver values
00060 static const double DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION_ = 0.005;
00061 static const double DEFAULT_KIN_SOLVER_TIMEOUT_ = 0.005;
00062 static const int DEFAULT_KIN_SOLVER_ATTEMPTS_ = 3;
00063 
00064 // ******************************************************************************************
00065 // Structs
00066 // ******************************************************************************************
00067 
00071 struct GroupMetaData
00072 {
00073   std::string kinematics_solver_;               // Name of kinematics plugin to use
00074   double kinematics_solver_search_resolution_;  // resolution to use with solver
00075   double kinematics_solver_timeout_;            // solver timeout
00076   int kinematics_solver_attempts_;              // solver attempts
00077 };
00078 
00082 struct OmplPlanningParameter
00083 {
00084   std::string name;     // name of parameter
00085   std::string value;    // value parameter will receive (but as a string)
00086   std::string comment;  // comment briefly describing what this parameter does
00087 };
00088 
00091 class OMPLPlannerDescription
00092 {
00093 public:
00098   OMPLPlannerDescription(const std::string& name, const std::string& type)
00099   {
00100     name_ = name;
00101     type_ = type;
00102   };
00104   ~OMPLPlannerDescription()
00105   {
00106     parameter_list_.clear();
00107   };
00113   void addParameter(const std::string& name, const std::string& value = "", const std::string& comment = "")
00114   {
00115     OmplPlanningParameter temp;
00116     temp.name = name;
00117     temp.value = value;
00118     temp.comment = comment;
00119     parameter_list_.push_back(temp);
00120   }
00121   std::vector<OmplPlanningParameter> parameter_list_;
00122   std::string name_;  // name of planner
00123   std::string type_;  // type of planner (geometric)
00124 };
00125 
00126 MOVEIT_CLASS_FORWARD(MoveItConfigData);
00127 
00134 class MoveItConfigData
00135 {
00136 public:
00137   MoveItConfigData();
00138   ~MoveItConfigData();
00139 
00140   // bits of information that can be entered in Setup Assistant
00141   enum InformationFields
00142   {
00143     COLLISIONS = 1 << 1,
00144     VIRTUAL_JOINTS = 1 << 2,
00145     GROUPS = 1 << 3,
00146     GROUP_CONTENTS = 1 << 4,
00147     GROUP_KINEMATICS = 1 << 5,
00148     POSES = 1 << 6,
00149     END_EFFECTORS = 1 << 7,
00150     PASSIVE_JOINTS = 1 << 8,
00151     AUTHOR_INFO = 1 << 9,
00152     SRDF = COLLISIONS | VIRTUAL_JOINTS | GROUPS | GROUP_CONTENTS | POSES | END_EFFECTORS | PASSIVE_JOINTS
00153   };
00154   unsigned long changes;  // bitfield of changes (composed of InformationFields)
00155 
00156   // All of the data needed for creating a MoveIt Configuration Files
00157 
00158   // ******************************************************************************************
00159   // URDF Data
00160   // ******************************************************************************************
00161 
00163   std::string urdf_path_;
00164 
00166   std::string urdf_pkg_name_;
00167 
00169   std::string urdf_pkg_relative_path_;
00170 
00172   bool urdf_requires_jade_xacro_;
00173 
00175   bool urdf_from_xacro_;
00176 
00178   boost::shared_ptr<urdf::Model> urdf_model_;
00179 
00180   // ******************************************************************************************
00181   // SRDF Data
00182   // ******************************************************************************************
00183 
00185   std::string srdf_path_;
00186 
00188   std::string srdf_pkg_relative_path_;
00189 
00191   srdf::SRDFWriterPtr srdf_;
00192 
00193   // ******************************************************************************************
00194   // Other Data
00195   // ******************************************************************************************
00196 
00198   std::map<std::string, GroupMetaData> group_meta_data_;
00199 
00201   std::string setup_assistant_path_;
00202 
00204   std::string config_pkg_path_;
00205 
00207   std::string template_package_path_;
00208 
00210   bool debug_;
00211 
00213   collision_detection::AllowedCollisionMatrix allowed_collision_matrix_;
00214 
00216   std::time_t config_pkg_generated_timestamp_;
00217 
00219   std::string author_name_;
00220 
00222   std::string author_email_;
00223 
00224   // ******************************************************************************************
00225   // Public Functions
00226   // ******************************************************************************************
00227 
00229   robot_model::RobotModelConstPtr getRobotModel();
00230 
00232   void updateRobotModel();
00233 
00235   planning_scene::PlanningScenePtr getPlanningScene();
00236 
00243   srdf::Model::Group* findGroupByName(const std::string& name);
00244 
00246   void loadAllowedCollisionMatrix();
00247 
00248   // ******************************************************************************************
00249   // Public Functions for outputting configuration and setting files
00250   // ******************************************************************************************
00251   bool outputSetupAssistantFile(const std::string& file_path);
00252   bool outputOMPLPlanningYAML(const std::string& file_path);
00253   bool outputKinematicsYAML(const std::string& file_path);
00254   bool outputJointLimitsYAML(const std::string& file_path);
00255   bool outputFakeControllersYAML(const std::string& file_path);
00256 
00262   void setCollisionLinkPairs(const moveit_setup_assistant::LinkPairMap& link_pairs, size_t skip_mask = 0);
00263 
00269   std::string decideProjectionJoints(std::string planning_group);
00270 
00276   bool inputKinematicsYAML(const std::string& file_path);
00277 
00283   bool setPackagePath(const std::string& pkg_path);
00284 
00290   bool getSetupAssistantYAMLPath(std::string& path);
00291 
00293   bool createFullURDFPath();
00294 
00296   bool createFullSRDFPath(const std::string& package_path);
00297 
00304   bool inputSetupAssistantYAML(const std::string& file_path);
00305 
00314   std::string appendPaths(const std::string& path1, const std::string& path2);
00315 
00322   struct joint_model_compare
00323   {
00324     bool operator()(const robot_model::JointModel* jm1, const robot_model::JointModel* jm2) const
00325     {
00326       return jm1->getName() < jm2->getName();
00327     }
00328   };
00329 
00330 private:
00331   // ******************************************************************************************
00332   // Private Vars
00333   // ******************************************************************************************
00334 
00335   // Shared kinematic model
00336   robot_model::RobotModelPtr robot_model_;
00337   robot_model::RobotModelConstPtr robot_model_const_;
00338 
00339   // Shared planning scene
00340   planning_scene::PlanningScenePtr planning_scene_;
00341 };
00342 
00343 }  // namespace
00344 
00345 #endif


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Wed Jun 19 2019 19:25:13