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
00035
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>
00042 #include <srdfdom/srdf_writer.h>
00043 #include <urdf/model.h>
00044 #include <moveit/macros/class_forward.h>
00045 #include <moveit/planning_scene/planning_scene.h>
00046 #include <moveit/collision_detection/collision_matrix.h>
00047 #include <moveit/setup_assistant/tools/compute_default_collisions.h>
00048
00049 namespace moveit_setup_assistant
00050 {
00051
00052
00053
00054
00055
00056 static const std::string ROBOT_DESCRIPTION = "robot_description";
00057 static const std::string MOVEIT_ROBOT_STATE = "moveit_robot_state";
00058
00059
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
00066
00067
00071 struct GroupMetaData
00072 {
00073 std::string kinematics_solver_;
00074 double kinematics_solver_search_resolution_;
00075 double kinematics_solver_timeout_;
00076 int kinematics_solver_attempts_;
00077 };
00078
00082 struct OmplPlanningParameter
00083 {
00084 std::string name;
00085 std::string value;
00086 std::string comment;
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_;
00123 std::string type_;
00124 };
00125
00126 MOVEIT_CLASS_FORWARD(MoveItConfigData);
00127
00134 class MoveItConfigData
00135 {
00136 public:
00137 MoveItConfigData();
00138 ~MoveItConfigData();
00139
00140
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;
00155
00156
00157
00158
00159
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_from_xacro_;
00173
00175 boost::shared_ptr<urdf::Model> urdf_model_;
00176
00177
00178
00179
00180
00182 std::string srdf_path_;
00183
00185 std::string srdf_pkg_relative_path_;
00186
00188 srdf::SRDFWriterPtr srdf_;
00189
00190
00191
00192
00193
00195 std::map<std::string, GroupMetaData> group_meta_data_;
00196
00198 std::string setup_assistant_path_;
00199
00201 std::string config_pkg_path_;
00202
00204 std::string template_package_path_;
00205
00207 bool debug_;
00208
00210 collision_detection::AllowedCollisionMatrix allowed_collision_matrix_;
00211
00213 std::time_t config_pkg_generated_timestamp_;
00214
00216 std::string author_name_;
00217
00219 std::string author_email_;
00220
00221
00222
00223
00224
00226 robot_model::RobotModelConstPtr getRobotModel();
00227
00229 void updateRobotModel();
00230
00232 planning_scene::PlanningScenePtr getPlanningScene();
00233
00240 srdf::Model::Group* findGroupByName(const std::string& name);
00241
00243 void loadAllowedCollisionMatrix();
00244
00245
00246
00247
00248 bool outputSetupAssistantFile(const std::string& file_path);
00249 bool outputOMPLPlanningYAML(const std::string& file_path);
00250 bool outputKinematicsYAML(const std::string& file_path);
00251 bool outputJointLimitsYAML(const std::string& file_path);
00252 bool outputFakeControllersYAML(const std::string& file_path);
00253
00259 void setCollisionLinkPairs(const moveit_setup_assistant::LinkPairMap& link_pairs, size_t skip_mask = 0);
00260
00266 std::string decideProjectionJoints(std::string planning_group);
00267
00273 bool inputKinematicsYAML(const std::string& file_path);
00274
00280 bool setPackagePath(const std::string& pkg_path);
00281
00287 bool getSetupAssistantYAMLPath(std::string& path);
00288
00290 bool createFullURDFPath();
00291
00293 bool createFullSRDFPath(const std::string& package_path);
00294
00301 bool inputSetupAssistantYAML(const std::string& file_path);
00302
00311 std::string appendPaths(const std::string& path1, const std::string& path2);
00312
00319 struct joint_model_compare
00320 {
00321 bool operator()(const robot_model::JointModel* jm1, const robot_model::JointModel* jm2) const
00322 {
00323 return jm1->getName() < jm2->getName();
00324 }
00325 };
00326
00327 private:
00328
00329
00330
00331
00332
00333 robot_model::RobotModelPtr robot_model_;
00334 robot_model::RobotModelConstPtr robot_model_const_;
00335
00336
00337 planning_scene::PlanningScenePtr planning_scene_;
00338 };
00339
00340 }
00341
00342 #endif