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 #include <moveit/setup_assistant/tools/moveit_config_data.h>
00038
00039 #include <iostream>
00040 #include <fstream>
00041 #include <yaml-cpp/yaml.h>
00042 #include <boost/filesystem.hpp>
00043 #include <boost/algorithm/string.hpp>
00044
00045 #ifdef HAVE_NEW_YAMLCPP
00046 #include <boost/optional.hpp>
00047 #endif
00048
00049
00050 #include <ros/console.h>
00051 #include <ros/package.h>
00052
00053 #ifdef HAVE_NEW_YAMLCPP
00054 namespace YAML
00055 {
00056
00057 class Iterator
00058 {
00059 public:
00060 typedef YAML::iterator iterator_t;
00061 typedef YAML::const_iterator const_iterator_t;
00062
00063 Iterator(iterator_t iter) : iter_(iter)
00064 {
00065 }
00066
00067 const Node& first() const
00068 {
00069 return iter_->first;
00070 }
00071
00072 const Node& second() const
00073 {
00074 return iter_->second;
00075 }
00076
00077 detail::iterator_value operator*()
00078 {
00079 return *iter_;
00080 }
00081
00082 Iterator operator++()
00083 {
00084 return Iterator(++iter_);
00085 }
00086
00087 bool operator==(iterator_t const& other) const
00088 {
00089 return iter_ == other;
00090 }
00091
00092 bool operator!=(iterator_t const& other) const
00093 {
00094 return iter_ != other;
00095 }
00096
00097 private:
00098 iterator_t iter_;
00099 };
00100 }
00101 #endif
00102
00103 namespace moveit_setup_assistant
00104 {
00105
00106 namespace fs = boost::filesystem;
00107
00108 #ifdef HAVE_NEW_YAMLCPP
00109 typedef boost::optional<YAML::Node> yaml_node_t;
00110
00111
00112 template <typename T>
00113 yaml_node_t findValue(const YAML::Node& node, const T& key)
00114 {
00115 if (node[key])
00116 return node[key];
00117 return yaml_node_t();
00118 }
00119
00120
00121
00122 template <typename T>
00123 void operator>>(const YAML::Node& node, T& i)
00124 {
00125 i = node.as<T>();
00126 }
00127
00128 #else
00129 typedef const YAML::Node* yaml_node_t;
00130
00131
00132 template <typename T>
00133 yaml_node_t findValue(const YAML::Node& node, const T& key)
00134 {
00135 return node.FindValue(key);
00136 }
00137 #endif
00138
00139
00140
00141 void loadYaml(std::istream& in_stream, YAML::Node& doc_out)
00142 {
00143 #ifdef HAVE_NEW_YAMLCPP
00144 doc_out = YAML::Load(in_stream);
00145 #else
00146 YAML::Parser parser(in_stream);
00147 parser.GetNextDocument(doc_out);
00148 #endif
00149 }
00150
00151
00152
00153
00154 MoveItConfigData::MoveItConfigData() : config_pkg_generated_timestamp_(0)
00155 {
00156
00157 srdf_.reset(new srdf::SRDFWriter());
00158 urdf_model_.reset(new urdf::Model());
00159
00160
00161 debug_ = false;
00162
00163
00164 setup_assistant_path_ = ros::package::getPath("moveit_setup_assistant");
00165 if (setup_assistant_path_.empty())
00166 {
00167 setup_assistant_path_ = ".";
00168 }
00169 }
00170
00171
00172
00173
00174 MoveItConfigData::~MoveItConfigData()
00175 {
00176 }
00177
00178
00179
00180
00181 robot_model::RobotModelConstPtr MoveItConfigData::getRobotModel()
00182 {
00183 if (!robot_model_)
00184 {
00185
00186 robot_model_.reset(new robot_model::RobotModel(urdf_model_, srdf_->srdf_model_));
00187 robot_model_const_ = robot_model_;
00188 }
00189
00190 return robot_model_const_;
00191 }
00192
00193
00194
00195
00196 void MoveItConfigData::updateRobotModel()
00197 {
00198 ROS_INFO("Updating kinematic model");
00199
00200
00201 srdf_->updateSRDFModel(*urdf_model_);
00202
00203
00204 robot_model_.reset(new robot_model::RobotModel(urdf_model_, srdf_->srdf_model_));
00205 robot_model_const_ = robot_model_;
00206
00207
00208 planning_scene_.reset();
00209 }
00210
00211
00212
00213
00214 planning_scene::PlanningScenePtr MoveItConfigData::getPlanningScene()
00215 {
00216 if (!planning_scene_)
00217 {
00218
00219 getRobotModel();
00220
00221
00222 planning_scene_.reset(new planning_scene::PlanningScene(robot_model_));
00223 }
00224 return planning_scene_;
00225 }
00226
00227
00228
00229
00230 void MoveItConfigData::loadAllowedCollisionMatrix()
00231 {
00232
00233 allowed_collision_matrix_.clear();
00234
00235
00236 for (std::vector<srdf::Model::DisabledCollision>::const_iterator pair_it = srdf_->disabled_collisions_.begin();
00237 pair_it != srdf_->disabled_collisions_.end(); ++pair_it)
00238 {
00239 allowed_collision_matrix_.setEntry(pair_it->link1_, pair_it->link2_, true);
00240 }
00241 }
00242
00243
00244
00245
00246 bool MoveItConfigData::outputSetupAssistantFile(const std::string& file_path)
00247 {
00248 YAML::Emitter emitter;
00249 emitter << YAML::BeginMap;
00250
00251
00252 emitter << YAML::Key << "moveit_setup_assistant_config";
00253
00254 emitter << YAML::Value << YAML::BeginMap;
00255
00256
00257 emitter << YAML::Key << "URDF";
00258 emitter << YAML::Value << YAML::BeginMap;
00259 emitter << YAML::Key << "package" << YAML::Value << urdf_pkg_name_;
00260 emitter << YAML::Key << "relative_path" << YAML::Value << urdf_pkg_relative_path_;
00261 emitter << YAML::EndMap;
00262
00264 emitter << YAML::Key << "SRDF";
00265 emitter << YAML::Value << YAML::BeginMap;
00266 emitter << YAML::Key << "relative_path" << YAML::Value << srdf_pkg_relative_path_;
00267 emitter << YAML::EndMap;
00268
00270 emitter << YAML::Key << "CONFIG";
00271 emitter << YAML::Value << YAML::BeginMap;
00272 emitter << YAML::Key << "author_name" << YAML::Value << author_name_;
00273 emitter << YAML::Key << "author_email" << YAML::Value << author_email_;
00274 emitter << YAML::Key << "generated_timestamp" << YAML::Value << std::time(NULL);
00275 emitter << YAML::EndMap;
00276
00277 emitter << YAML::EndMap;
00278
00279 std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
00280 if (!output_stream.good())
00281 {
00282 ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
00283 return false;
00284 }
00285
00286 output_stream << emitter.c_str();
00287 output_stream.close();
00288
00289 return true;
00290 }
00291
00292
00293
00294
00295 bool MoveItConfigData::outputOMPLPlanningYAML(const std::string& file_path)
00296 {
00297 YAML::Emitter emitter;
00298 emitter << YAML::BeginMap;
00299
00300
00301 emitter << YAML::Key << "planner_configs";
00302
00303 emitter << YAML::Value << YAML::BeginMap;
00304
00305 std::vector<OMPLPlannerDescription> planner_des;
00306
00307 OMPLPlannerDescription SBL("SBL", "geometric");
00308 SBL.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()");
00309 planner_des.push_back(SBL);
00310
00311 OMPLPlannerDescription EST("EST", "geometric");
00312 EST.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()");
00313 EST.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
00314 planner_des.push_back(EST);
00315
00316 OMPLPlannerDescription LBKPIECE("LBKPIECE", "geometric");
00317 LBKPIECE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
00318 "setup()");
00319 LBKPIECE.addParameter("border_fraction", "0.9", "Fraction of time focused on boarder default: 0.9");
00320 LBKPIECE.addParameter("min_valid_path_fraction", "0.5", "Accept partially valid moves above fraction. default: 0.5");
00321 planner_des.push_back(LBKPIECE);
00322
00323 OMPLPlannerDescription BKPIECE("BKPIECE", "geometric");
00324 BKPIECE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
00325 "setup()");
00326 BKPIECE.addParameter("border_fraction", "0.9", "Fraction of time focused on boarder default: 0.9");
00327 BKPIECE.addParameter("failed_expansion_score_factor", "0.5", "When extending motion fails, scale score by factor. "
00328 "default: 0.5");
00329 BKPIECE.addParameter("min_valid_path_fraction", "0.5", "Accept partially valid moves above fraction. default: 0.5");
00330 planner_des.push_back(BKPIECE);
00331
00332 OMPLPlannerDescription KPIECE("KPIECE", "geometric");
00333 KPIECE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
00334 "setup()");
00335 KPIECE.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05 ");
00336 KPIECE.addParameter("border_fraction", "0.9", "Fraction of time focused on boarder default: 0.9 (0.0,1.]");
00337 KPIECE.addParameter("failed_expansion_score_factor", "0.5", "When extending motion fails, scale score by factor. "
00338 "default: 0.5");
00339 KPIECE.addParameter("min_valid_path_fraction", "0.5", "Accept partially valid moves above fraction. default: 0.5");
00340 planner_des.push_back(KPIECE);
00341
00342 OMPLPlannerDescription RRT("RRT", "geometric");
00343 RRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()");
00344 RRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
00345 planner_des.push_back(RRT);
00346
00347 OMPLPlannerDescription RRTConnect("RRTConnect", "geometric");
00348 RRTConnect.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
00349 "setup()");
00350 planner_des.push_back(RRTConnect);
00351
00352 OMPLPlannerDescription RRTstar("RRTstar", "geometric");
00353 RRTstar.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
00354 "setup()");
00355 RRTstar.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
00356 RRTstar.addParameter("delay_collision_checking", "1", "Stop collision checking as soon as C-free parent found. "
00357 "default 1");
00358 planner_des.push_back(RRTstar);
00359
00360 OMPLPlannerDescription TRRT("TRRT", "geometric");
00361 TRRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()");
00362 TRRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
00363 TRRT.addParameter("max_states_failed", "10", "when to start increasing temp. default: 10");
00364 TRRT.addParameter("temp_change_factor", "2.0", "how much to increase or decrease temp. default: 2.0");
00365 TRRT.addParameter("min_temperature", "10e-10", "lower limit of temp change. default: 10e-10");
00366 TRRT.addParameter("init_temperature", "10e-6", "initial temperature. default: 10e-6");
00367 TRRT.addParameter("frountier_threshold", "0.0", "dist new state to nearest neighbor to disqualify as frontier. "
00368 "default: 0.0 set in setup() ");
00369 TRRT.addParameter("frountierNodeRatio", "0.1", "1/10, or 1 nonfrontier for every 10 frontier. default: 0.1");
00370 TRRT.addParameter("k_constant", "0.0", "value used to normalize expresssion. default: 0.0 set in setup()");
00371 planner_des.push_back(TRRT);
00372
00373 OMPLPlannerDescription PRM("PRM", "geometric");
00374 PRM.addParameter("max_nearest_neighbors", "10", "use k nearest neighbors. default: 10");
00375 planner_des.push_back(PRM);
00376
00377 OMPLPlannerDescription PRMstar("PRMstar", "geometric");
00378 planner_des.push_back(PRMstar);
00379
00380
00381 std::vector<std::string> pconfigs;
00382 for (std::size_t i = 0; i < planner_des.size(); ++i)
00383 {
00384 std::string defaultconfig = planner_des[i].name_ + "kConfigDefault";
00385 emitter << YAML::Key << defaultconfig;
00386 emitter << YAML::Value << YAML::BeginMap;
00387 emitter << YAML::Key << "type" << YAML::Value << "geometric::" + planner_des[i].name_;
00388 for (std::size_t j = 0; j < planner_des[i].parameter_list_.size(); j++)
00389 {
00390 emitter << YAML::Key << planner_des[i].parameter_list_[j].name;
00391 emitter << YAML::Value << planner_des[i].parameter_list_[j].value;
00392 emitter << YAML::Comment(planner_des[i].parameter_list_[j].comment.c_str());
00393 }
00394 emitter << YAML::EndMap;
00395
00396 pconfigs.push_back(defaultconfig);
00397 }
00398
00399
00400 emitter << YAML::EndMap;
00401
00402
00403 for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
00404 ++group_it)
00405 {
00406 emitter << YAML::Key << group_it->name_;
00407 emitter << YAML::Value << YAML::BeginMap;
00408
00409 emitter << YAML::Key << "planner_configs";
00410 emitter << YAML::Value << YAML::BeginSeq;
00411 for (std::size_t i = 0; i < pconfigs.size(); ++i)
00412 emitter << pconfigs[i];
00413 emitter << YAML::EndSeq;
00414
00415
00416 std::string projection_joints = decideProjectionJoints(group_it->name_);
00417 if (!projection_joints.empty())
00418 {
00419 emitter << YAML::Key << "projection_evaluator";
00420 emitter << YAML::Value << projection_joints;
00421 emitter << YAML::Key << "longest_valid_segment_fraction";
00422 emitter << YAML::Value << "0.05";
00423 }
00424
00425 emitter << YAML::EndMap;
00426 }
00427
00428 emitter << YAML::EndMap;
00429
00430 std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
00431 if (!output_stream.good())
00432 {
00433 ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
00434 return false;
00435 }
00436
00437 output_stream << emitter.c_str();
00438 output_stream.close();
00439
00440 return true;
00441 }
00442
00443
00444
00445
00446 bool MoveItConfigData::outputKinematicsYAML(const std::string& file_path)
00447 {
00448 YAML::Emitter emitter;
00449 emitter << YAML::BeginMap;
00450
00451
00452 for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
00453 ++group_it)
00454 {
00455
00456 if (group_meta_data_[group_it->name_].kinematics_solver_.empty() ||
00457 group_meta_data_[group_it->name_].kinematics_solver_ == "None")
00458 continue;
00459
00460 emitter << YAML::Key << group_it->name_;
00461 emitter << YAML::Value << YAML::BeginMap;
00462
00463
00464 emitter << YAML::Key << "kinematics_solver";
00465 emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_;
00466
00467
00468 emitter << YAML::Key << "kinematics_solver_search_resolution";
00469 emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_search_resolution_;
00470
00471
00472 emitter << YAML::Key << "kinematics_solver_timeout";
00473 emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_timeout_;
00474
00475
00476 emitter << YAML::Key << "kinematics_solver_attempts";
00477 emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_attempts_;
00478
00479 emitter << YAML::EndMap;
00480 }
00481
00482 emitter << YAML::EndMap;
00483
00484 std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
00485 if (!output_stream.good())
00486 {
00487 ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
00488 return false;
00489 }
00490
00491 output_stream << emitter.c_str();
00492 output_stream.close();
00493
00494 return true;
00495 }
00496
00497 bool MoveItConfigData::outputFakeControllersYAML(const std::string& file_path)
00498 {
00499 YAML::Emitter emitter;
00500 emitter << YAML::BeginMap;
00501
00502 emitter << YAML::Key << "controller_list";
00503 emitter << YAML::Value << YAML::BeginSeq;
00504
00505
00506 std::set<const robot_model::JointModel*> joints;
00507
00508
00509 for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
00510 ++group_it)
00511 {
00512
00513 const robot_model::JointModelGroup* joint_model_group = getRobotModel()->getJointModelGroup(group_it->name_);
00514 emitter << YAML::BeginMap;
00515 const std::vector<const robot_model::JointModel*>& joint_models = joint_model_group->getActiveJointModels();
00516 emitter << YAML::Key << "name";
00517 emitter << YAML::Value << "fake_" + group_it->name_ + "_controller";
00518 emitter << YAML::Key << "joints";
00519 emitter << YAML::Value << YAML::BeginSeq;
00520
00521
00522 for (std::vector<const robot_model::JointModel*>::const_iterator joint_it = joint_models.begin();
00523 joint_it != joint_models.end(); ++joint_it)
00524 {
00525 emitter << (*joint_it)->getName();
00526 }
00527 emitter << YAML::EndSeq;
00528 emitter << YAML::EndMap;
00529 }
00530 emitter << YAML::EndSeq;
00531 emitter << YAML::EndMap;
00532
00533 std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
00534 if (!output_stream.good())
00535 {
00536 ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
00537 return false;
00538 }
00539
00540 output_stream << emitter.c_str();
00541 output_stream.close();
00542
00543 return true;
00544 }
00545
00546
00547
00548
00549 bool MoveItConfigData::outputJointLimitsYAML(const std::string& file_path)
00550 {
00551 YAML::Emitter emitter;
00552 emitter << YAML::BeginMap;
00553
00554 emitter << YAML::Key << "joint_limits";
00555 emitter << YAML::Value << YAML::BeginMap;
00556
00557
00558 std::set<const robot_model::JointModel*, joint_model_compare> joints;
00559
00560
00561 for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
00562 ++group_it)
00563 {
00564
00565 const robot_model::JointModelGroup* joint_model_group = getRobotModel()->getJointModelGroup(group_it->name_);
00566
00567 const std::vector<const robot_model::JointModel*>& joint_models = joint_model_group->getJointModels();
00568
00569
00570 for (std::vector<const robot_model::JointModel*>::const_iterator joint_it = joint_models.begin();
00571 joint_it != joint_models.end(); ++joint_it)
00572 {
00573
00574 if ((*joint_it)->getVariableCount() == 1)
00575 joints.insert(*joint_it);
00576 }
00577 }
00578
00579
00580 for (std::set<const robot_model::JointModel*>::iterator joint_it = joints.begin(); joint_it != joints.end();
00581 ++joint_it)
00582 {
00583 emitter << YAML::Key << (*joint_it)->getName();
00584 emitter << YAML::Value << YAML::BeginMap;
00585
00586 const robot_model::VariableBounds& b = (*joint_it)->getVariableBounds()[0];
00587
00588
00589 emitter << YAML::Key << "has_velocity_limits";
00590 if (b.velocity_bounded_)
00591 emitter << YAML::Value << "true";
00592 else
00593 emitter << YAML::Value << "false";
00594
00595
00596 emitter << YAML::Key << "max_velocity";
00597 emitter << YAML::Value << std::min(fabs(b.max_velocity_), fabs(b.min_velocity_));
00598
00599
00600 emitter << YAML::Key << "has_acceleration_limits";
00601 if (b.acceleration_bounded_)
00602 emitter << YAML::Value << "true";
00603 else
00604 emitter << YAML::Value << "false";
00605
00606
00607 emitter << YAML::Key << "max_acceleration";
00608 emitter << YAML::Value << std::min(fabs(b.max_acceleration_), fabs(b.min_acceleration_));
00609
00610 emitter << YAML::EndMap;
00611 }
00612
00613 emitter << YAML::EndMap;
00614
00615 std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
00616 if (!output_stream.good())
00617 {
00618 ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
00619 return false;
00620 }
00621
00622 output_stream << "# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or "
00623 "augmented as needed"
00624 << std::endl;
00625 output_stream << "# Specific joint properties can be changed with the keys [max_position, min_position, "
00626 "max_velocity, max_acceleration]"
00627 << std::endl;
00628 output_stream << "# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]" << std::endl;
00629 output_stream << emitter.c_str();
00630 output_stream.close();
00631
00632 return true;
00633 }
00634
00635
00636
00637
00638
00639 class SortableDisabledCollision
00640 {
00641 public:
00642 SortableDisabledCollision(const srdf::Model::DisabledCollision& dc)
00643 : dc_(dc), key_(dc.link1_ < dc.link2_ ? (dc.link1_ + "|" + dc.link2_) : (dc.link2_ + "|" + dc.link1_))
00644 {
00645 }
00646 operator const srdf::Model::DisabledCollision() const
00647 {
00648 return dc_;
00649 }
00650 bool operator<(const SortableDisabledCollision& other) const
00651 {
00652 return key_ < other.key_;
00653 }
00654
00655 private:
00656 const srdf::Model::DisabledCollision dc_;
00657 const std::string key_;
00658 };
00659
00660 void MoveItConfigData::setCollisionLinkPairs(const moveit_setup_assistant::LinkPairMap& link_pairs, size_t skip_mask)
00661 {
00662
00663 srdf::Model::DisabledCollision dc;
00664
00665 std::set<SortableDisabledCollision> disabled_collisions;
00666 disabled_collisions.insert(srdf_->disabled_collisions_.begin(), srdf_->disabled_collisions_.end());
00667
00668
00669 for (moveit_setup_assistant::LinkPairMap::const_iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end();
00670 ++pair_it)
00671 {
00672
00673 if (pair_it->second.disable_check)
00674 {
00675 if ((1 << pair_it->second.reason) & skip_mask)
00676 continue;
00677
00678 dc.link1_ = pair_it->first.first;
00679 dc.link2_ = pair_it->first.second;
00680 dc.reason_ = moveit_setup_assistant::disabledReasonToString(pair_it->second.reason);
00681
00682 disabled_collisions.insert(SortableDisabledCollision(dc));
00683 }
00684 }
00685
00686 srdf_->disabled_collisions_.assign(disabled_collisions.begin(), disabled_collisions.end());
00687 }
00688
00689
00690
00691
00692 std::string MoveItConfigData::decideProjectionJoints(std::string planning_group)
00693 {
00694 std::string joint_pair = "";
00695
00696
00697 const robot_model::RobotModelConstPtr& model = getRobotModel();
00698
00699
00700 if (!model->hasJointModelGroup(planning_group))
00701 return joint_pair;
00702
00703
00704 const robot_model::JointModelGroup* group = model->getJointModelGroup(planning_group);
00705
00706
00707 const std::vector<std::string> joints = group->getJointModelNames();
00708
00709 if (joints.size() >= 2)
00710 {
00711
00712 if (group->getJointModel(joints[0])->getVariableCount() == 1 &&
00713 group->getJointModel(joints[1])->getVariableCount() == 1)
00714 {
00715
00716 joint_pair = "joints(" + joints[0] + "," + joints[1] + ")";
00717 }
00718 }
00719
00720 return joint_pair;
00721 }
00722
00723
00724
00725
00726 bool MoveItConfigData::inputKinematicsYAML(const std::string& file_path)
00727 {
00728
00729 std::ifstream input_stream(file_path.c_str());
00730 if (!input_stream.good())
00731 {
00732 ROS_ERROR_STREAM("Unable to open file for reading " << file_path);
00733 return false;
00734 }
00735
00736
00737 try
00738 {
00739 YAML::Node doc;
00740 loadYaml(input_stream, doc);
00741
00742 yaml_node_t prop_name;
00743
00744
00745 #ifdef HAVE_NEW_YAMLCPP
00746 for (YAML::const_iterator group_it = doc.begin(); group_it != doc.end(); ++group_it)
00747 #else
00748 for (YAML::Iterator group_it = doc.begin(); group_it != doc.end(); ++group_it)
00749 #endif
00750 {
00751 #ifdef HAVE_NEW_YAMLCPP
00752 const std::string group_name = group_it->first.as<std::string>();
00753 #else
00754 std::string group_name;
00755 group_it.first() >> group_name;
00756 #endif
00757
00758
00759 GroupMetaData new_meta_data;
00760
00761
00762 #ifdef HAVE_NEW_YAMLCPP
00763 if (prop_name = findValue(group_it->second, "kinematics_solver"))
00764 #else
00765 if (prop_name = findValue(group_it.second(), "kinematics_solver"))
00766 #endif
00767 {
00768 *prop_name >> new_meta_data.kinematics_solver_;
00769 }
00770
00771
00772 #ifdef HAVE_NEW_YAMLCPP
00773 if (prop_name = findValue(group_it->second, "kinematics_solver_search_resolution"))
00774 #else
00775 if (prop_name = findValue(group_it.second(), "kinematics_solver_search_resolution"))
00776 #endif
00777 {
00778 *prop_name >> new_meta_data.kinematics_solver_search_resolution_;
00779 }
00780 else
00781 {
00782 new_meta_data.kinematics_solver_attempts_ = DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION_;
00783 }
00784
00785
00786 #ifdef HAVE_NEW_YAMLCPP
00787 if (prop_name = findValue(group_it->second, "kinematics_solver_timeout"))
00788 #else
00789 if (prop_name = findValue(group_it.second(), "kinematics_solver_timeout"))
00790 #endif
00791 {
00792 *prop_name >> new_meta_data.kinematics_solver_timeout_;
00793 }
00794 else
00795 {
00796 new_meta_data.kinematics_solver_attempts_ = DEFAULT_KIN_SOLVER_TIMEOUT_;
00797 }
00798
00799
00800 #ifdef HAVE_NEW_YAMLCPP
00801 if (prop_name = findValue(group_it->second, "kinematics_solver_attempts"))
00802 #else
00803 if (prop_name = findValue(group_it.second(), "kinematics_solver_attempts"))
00804 #endif
00805 {
00806 *prop_name >> new_meta_data.kinematics_solver_attempts_;
00807 }
00808 else
00809 {
00810 new_meta_data.kinematics_solver_attempts_ = DEFAULT_KIN_SOLVER_ATTEMPTS_;
00811 }
00812
00813
00814 group_meta_data_[group_name] = new_meta_data;
00815 }
00816 }
00817 catch (YAML::ParserException& e)
00818 {
00819 ROS_ERROR_STREAM(e.what());
00820 return false;
00821 }
00822
00823 return true;
00824 }
00825
00826
00827
00828
00829 bool MoveItConfigData::setPackagePath(const std::string& pkg_path)
00830 {
00831 std::string full_package_path;
00832
00833
00834 if (!fs::is_directory(pkg_path))
00835 {
00836
00837 full_package_path = ros::package::getPath(pkg_path);
00838
00839
00840 if (!fs::is_directory(full_package_path))
00841 {
00842 return false;
00843 }
00844 }
00845 else
00846 {
00847
00848 full_package_path = pkg_path;
00849 }
00850
00851 config_pkg_path_ = full_package_path;
00852 return true;
00853 }
00854
00855
00856
00857
00858
00859 bool MoveItConfigData::getSetupAssistantYAMLPath(std::string& path)
00860 {
00861 path = appendPaths(config_pkg_path_, ".setup_assistant");
00862
00863
00864 return fs::is_regular_file(path);
00865 }
00866
00867
00868
00869
00870 bool MoveItConfigData::createFullURDFPath()
00871 {
00872 boost::trim(urdf_pkg_name_);
00873
00874
00875 if (urdf_pkg_name_.empty() || urdf_pkg_name_ == "\"\"")
00876 {
00877 urdf_path_ = urdf_pkg_relative_path_;
00878 urdf_pkg_name_.clear();
00879 }
00880 else
00881 {
00882
00883 std::string robot_desc_pkg_path = ros::package::getPath(urdf_pkg_name_);
00884
00885 if (robot_desc_pkg_path.empty())
00886 {
00887 urdf_path_.clear();
00888 return false;
00889 }
00890
00891
00892 urdf_path_ = appendPaths(robot_desc_pkg_path, urdf_pkg_relative_path_);
00893 }
00894
00895
00896 return fs::is_regular_file(urdf_path_);
00897 }
00898
00899
00900
00901
00902 bool MoveItConfigData::createFullSRDFPath(const std::string& package_path)
00903 {
00904 srdf_path_ = appendPaths(package_path, srdf_pkg_relative_path_);
00905
00906 return fs::is_regular_file(srdf_path_);
00907 }
00908
00909
00910
00911
00912 bool MoveItConfigData::inputSetupAssistantYAML(const std::string& file_path)
00913 {
00914
00915 std::ifstream input_stream(file_path.c_str());
00916 if (!input_stream.good())
00917 {
00918 ROS_ERROR_STREAM("Unable to open file for reading " << file_path);
00919 return false;
00920 }
00921
00922
00923 try
00924 {
00925 YAML::Node doc;
00926 loadYaml(input_stream, doc);
00927
00928 yaml_node_t title_node, urdf_node, package_node, srdf_node, relative_node, config_node, timestamp_node,
00929 author_name_node, author_email_node;
00930
00931
00932 if (title_node = findValue(doc, "moveit_setup_assistant_config"))
00933 {
00934
00935 if (urdf_node = findValue(*title_node, "URDF"))
00936 {
00937
00938 if (package_node = findValue(*urdf_node, "package"))
00939 {
00940 *package_node >> urdf_pkg_name_;
00941 }
00942 else
00943 {
00944 return false;
00945 }
00946
00947
00948 if (relative_node = findValue(*urdf_node, "relative_path"))
00949 {
00950 *relative_node >> urdf_pkg_relative_path_;
00951 }
00952 else
00953 {
00954 return false;
00955 }
00956 }
00957
00958 if (srdf_node = findValue(*title_node, "SRDF"))
00959 {
00960
00961 if (relative_node = findValue(*srdf_node, "relative_path"))
00962 {
00963 *relative_node >> srdf_pkg_relative_path_;
00964 }
00965 else
00966 {
00967 return false;
00968 }
00969 }
00970
00971 if (config_node = findValue(*title_node, "CONFIG"))
00972 {
00973
00974 if (author_name_node = findValue(*config_node, "author_name"))
00975 {
00976 *author_name_node >> author_name_;
00977 }
00978 if (author_email_node = findValue(*config_node, "author_email"))
00979 {
00980 *author_email_node >> author_email_;
00981 }
00982
00983 if (timestamp_node = findValue(*config_node, "generated_timestamp"))
00984 {
00985 *timestamp_node >> config_pkg_generated_timestamp_;
00986 }
00987 else
00988 {
00989
00990 }
00991 }
00992 return true;
00993 }
00994 }
00995 catch (YAML::ParserException& e)
00996 {
00997 ROS_ERROR_STREAM(e.what());
00998 }
00999
01000 return false;
01001 }
01002
01003
01004
01005
01006 std::string MoveItConfigData::appendPaths(const std::string& path1, const std::string& path2)
01007 {
01008 fs::path result = path1;
01009 result /= path2;
01010 return result.make_preferred().native().c_str();
01011 }
01012
01013 srdf::Model::Group* MoveItConfigData::findGroupByName(const std::string& name)
01014 {
01015
01016 srdf::Model::Group* searched_group = NULL;
01017
01018 for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
01019 ++group_it)
01020 {
01021 if (group_it->name_ == name)
01022 {
01023 searched_group = &(*group_it);
01024 break;
01025 }
01026 }
01027
01028
01029 if (searched_group == NULL)
01030 ROS_FATAL_STREAM("An internal error has occured while searching for groups. Group '" << name << "' was not found "
01031 "in the SRDF.");
01032
01033 return searched_group;
01034 }
01035
01036 }