moveit_config_data.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman */
36 
38 // Reading/Writing Files
39 #include <iostream> // For writing yaml and launch files
40 #include <fstream>
41 #include <boost/filesystem.hpp> // for creating folders/files
42 #include <boost/algorithm/string.hpp> // for string find and replace in templates
43 
44 // ROS
45 #include <ros/console.h>
46 #include <ros/package.h> // for getting file path for loading images
47 
48 namespace moveit_setup_assistant
49 {
50 // File system
51 namespace fs = boost::filesystem;
52 
53 // ******************************************************************************************
54 // Constructor
55 // ******************************************************************************************
56 MoveItConfigData::MoveItConfigData() : config_pkg_generated_timestamp_(0)
57 {
58  // Create an instance of SRDF writer and URDF model for all widgets to share
59  srdf_.reset(new srdf::SRDFWriter());
60  urdf_model_.reset(new urdf::Model());
61 
62  // Not in debug mode
63  debug_ = false;
64 
65  // Get MoveIt! Setup Assistant package path
66  setup_assistant_path_ = ros::package::getPath("moveit_setup_assistant");
67  if (setup_assistant_path_.empty())
68  {
70  }
71 }
72 
73 // ******************************************************************************************
74 // Destructor
75 // ******************************************************************************************
77 {
78 }
79 
80 // ******************************************************************************************
81 // Load a robot model
82 // ******************************************************************************************
83 void MoveItConfigData::setRobotModel(robot_model::RobotModelPtr robot_model)
84 {
85  robot_model_ = robot_model;
86 }
87 
88 // ******************************************************************************************
89 // Provide a kinematic model. Load a new one if necessary
90 // ******************************************************************************************
91 robot_model::RobotModelConstPtr MoveItConfigData::getRobotModel()
92 {
93  if (!robot_model_)
94  {
95  // Initialize with a URDF Model Interface and a SRDF Model
96  robot_model_.reset(new robot_model::RobotModel(urdf_model_, srdf_->srdf_model_));
97  }
98 
99  return robot_model_;
100 }
101 
102 // ******************************************************************************************
103 // Update the Kinematic Model with latest SRDF modifications
104 // ******************************************************************************************
106 {
107  ROS_INFO("Updating kinematic model");
108 
109  // Tell SRDF Writer to create new SRDF Model, use original URDF model
110  srdf_->updateSRDFModel(*urdf_model_);
111 
112  // Create new kin model
113  robot_model_.reset(new robot_model::RobotModel(urdf_model_, srdf_->srdf_model_));
114 
115  // Reset the planning scene
116  planning_scene_.reset();
117 }
118 
119 // ******************************************************************************************
120 // Provide a shared planning scene
121 // ******************************************************************************************
122 planning_scene::PlanningScenePtr MoveItConfigData::getPlanningScene()
123 {
124  if (!planning_scene_)
125  {
126  // make sure kinematic model exists
127  getRobotModel();
128 
129  // Allocate an empty planning scene
131  }
132  return planning_scene_;
133 }
134 
135 // ******************************************************************************************
136 // Load the allowed collision matrix from the SRDF's list of link pairs
137 // ******************************************************************************************
139 {
140  // Clear the allowed collision matrix
142 
143  // Update the allowed collision matrix, in case there has been a change
144  for (std::vector<srdf::Model::DisabledCollision>::const_iterator pair_it = srdf_->disabled_collisions_.begin();
145  pair_it != srdf_->disabled_collisions_.end(); ++pair_it)
146  {
147  allowed_collision_matrix_.setEntry(pair_it->link1_, pair_it->link2_, true);
148  }
149 }
150 
151 // ******************************************************************************************
152 // Output MoveIt! Setup Assistant hidden settings file
153 // ******************************************************************************************
154 bool MoveItConfigData::outputSetupAssistantFile(const std::string& file_path)
155 {
156  YAML::Emitter emitter;
157  emitter << YAML::BeginMap;
158 
159  // Output every available planner ---------------------------------------------------
160  emitter << YAML::Key << "moveit_setup_assistant_config";
161 
162  emitter << YAML::Value << YAML::BeginMap;
163 
164  // URDF Path Location
165  emitter << YAML::Key << "URDF";
166  emitter << YAML::Value << YAML::BeginMap;
167  emitter << YAML::Key << "package" << YAML::Value << urdf_pkg_name_;
168  emitter << YAML::Key << "relative_path" << YAML::Value << urdf_pkg_relative_path_;
169  emitter << YAML::Key << "xacro_args" << YAML::Value << xacro_args_;
170  emitter << YAML::EndMap;
171 
173  emitter << YAML::Key << "SRDF";
174  emitter << YAML::Value << YAML::BeginMap;
175  emitter << YAML::Key << "relative_path" << YAML::Value << srdf_pkg_relative_path_;
176  emitter << YAML::EndMap;
177 
179  emitter << YAML::Key << "CONFIG";
180  emitter << YAML::Value << YAML::BeginMap;
181  emitter << YAML::Key << "author_name" << YAML::Value << author_name_;
182  emitter << YAML::Key << "author_email" << YAML::Value << author_email_;
183  emitter << YAML::Key << "generated_timestamp" << YAML::Value << std::time(NULL); // TODO: is this cross-platform?
184  emitter << YAML::EndMap;
185 
186  emitter << YAML::EndMap;
187 
188  std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
189  if (!output_stream.good())
190  {
191  ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
192  return false;
193  }
194 
195  output_stream << emitter.c_str();
196  output_stream.close();
197 
198  return true; // file created successfully
199 }
200 
201 // ******************************************************************************************
202 // Output OMPL Planning config files
203 // ******************************************************************************************
204 bool MoveItConfigData::outputOMPLPlanningYAML(const std::string& file_path)
205 {
206  YAML::Emitter emitter;
207  emitter << YAML::BeginMap;
208 
209  // Output every available planner ---------------------------------------------------
210  emitter << YAML::Key << "planner_configs";
211 
212  emitter << YAML::Value << YAML::BeginMap;
213 
214  std::vector<OMPLPlannerDescription> planner_des = getOMPLPlanners();
215 
216  // Add Planners with parameter values
217  std::vector<std::string> pconfigs;
218  for (std::size_t i = 0; i < planner_des.size(); ++i)
219  {
220  std::string defaultconfig = planner_des[i].name_;
221  emitter << YAML::Key << defaultconfig;
222  emitter << YAML::Value << YAML::BeginMap;
223  emitter << YAML::Key << "type" << YAML::Value << "geometric::" + planner_des[i].name_;
224  for (std::size_t j = 0; j < planner_des[i].parameter_list_.size(); j++)
225  {
226  emitter << YAML::Key << planner_des[i].parameter_list_[j].name;
227  emitter << YAML::Value << planner_des[i].parameter_list_[j].value;
228  emitter << YAML::Comment(planner_des[i].parameter_list_[j].comment.c_str());
229  }
230  emitter << YAML::EndMap;
231 
232  pconfigs.push_back(defaultconfig);
233  }
234 
235  // End of every avail planner
236  emitter << YAML::EndMap;
237 
238  // Output every group and the planners it can use ----------------------------------
239  for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
240  ++group_it)
241  {
242  emitter << YAML::Key << group_it->name_;
243  emitter << YAML::Value << YAML::BeginMap;
244  // Output associated planners
245  emitter << YAML::Key << "default_planner_config" << YAML::Value
246  << group_meta_data_[group_it->name_].default_planner_;
247  emitter << YAML::Key << "planner_configs";
248  emitter << YAML::Value << YAML::BeginSeq;
249  for (std::size_t i = 0; i < pconfigs.size(); ++i)
250  emitter << pconfigs[i];
251  emitter << YAML::EndSeq;
252 
253  // Output projection_evaluator
254  std::string projection_joints = decideProjectionJoints(group_it->name_);
255  if (!projection_joints.empty())
256  {
257  emitter << YAML::Key << "projection_evaluator";
258  emitter << YAML::Value << projection_joints;
259  // OMPL collision checking discretization
260  emitter << YAML::Key << "longest_valid_segment_fraction";
261  emitter << YAML::Value << "0.005";
262  }
263 
264  emitter << YAML::EndMap;
265  }
266 
267  emitter << YAML::EndMap;
268 
269  std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
270  if (!output_stream.good())
271  {
272  ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
273  return false;
274  }
275 
276  output_stream << emitter.c_str();
277  output_stream.close();
278 
279  return true; // file created successfully
280 }
281 
282 // ******************************************************************************************
283 // Output CHOMP Planning config files
284 // ******************************************************************************************
285 bool MoveItConfigData::outputCHOMPPlanningYAML(const std::string& file_path)
286 {
287  YAML::Emitter emitter;
288 
289  emitter << YAML::Value << YAML::BeginMap;
290  emitter << YAML::Key << "planning_time_limit" << YAML::Value << "10.0";
291  emitter << YAML::Key << "max_iterations" << YAML::Value << "200";
292  emitter << YAML::Key << "max_iterations_after_collision_free" << YAML::Value << "5";
293  emitter << YAML::Key << "smoothness_cost_weight" << YAML::Value << "0.1";
294  emitter << YAML::Key << "obstacle_cost_weight" << YAML::Value << "1.0";
295  emitter << YAML::Key << "learning_rate" << YAML::Value << "0.01";
296  emitter << YAML::Key << "smoothness_cost_velocity" << YAML::Value << "0.0";
297  emitter << YAML::Key << "smoothness_cost_acceleration" << YAML::Value << "1.0";
298  emitter << YAML::Key << "smoothness_cost_jerk" << YAML::Value << "0.0";
299  emitter << YAML::Key << "ridge_factor" << YAML::Value << "0.01";
300  emitter << YAML::Key << "use_pseudo_inverse" << YAML::Value << "false";
301  emitter << YAML::Key << "pseudo_inverse_ridge_factor" << YAML::Value << "1e-4";
302  emitter << YAML::Key << "joint_update_limit" << YAML::Value << "0.1";
303  emitter << YAML::Key << "collision_clearence" << YAML::Value << "0.2";
304  emitter << YAML::Key << "collision_threshold" << YAML::Value << "0.07";
305  emitter << YAML::Key << "use_stochastic_descent" << YAML::Value << "true";
306  emitter << YAML::Key << "enable_failure_recovery" << YAML::Value << "true";
307  emitter << YAML::Key << "max_recovery_attempts" << YAML::Value << "5";
308  emitter << YAML::EndMap;
309 
310  std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
311  if (!output_stream.good())
312  {
313  ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
314  return false;
315  }
316 
317  output_stream << emitter.c_str();
318  output_stream.close();
319 
320  return true; // file created successfully
321 }
322 
323 // ******************************************************************************************
324 // Output kinematic config files
325 // ******************************************************************************************
326 bool MoveItConfigData::outputKinematicsYAML(const std::string& file_path)
327 {
328  YAML::Emitter emitter;
329  emitter << YAML::BeginMap;
330 
331  // Output every group and the kinematic solver it can use ----------------------------------
332  for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
333  ++group_it)
334  {
335  // Only save kinematic data if the solver is not "None"
336  if (group_meta_data_[group_it->name_].kinematics_solver_.empty() ||
337  group_meta_data_[group_it->name_].kinematics_solver_ == "None")
338  continue;
339 
340  emitter << YAML::Key << group_it->name_;
341  emitter << YAML::Value << YAML::BeginMap;
342 
343  // Kinematic Solver
344  emitter << YAML::Key << "kinematics_solver";
345  emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_;
346 
347  // Search Resolution
348  emitter << YAML::Key << "kinematics_solver_search_resolution";
349  emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_search_resolution_;
350 
351  // Solver Timeout
352  emitter << YAML::Key << "kinematics_solver_timeout";
353  emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_timeout_;
354 
355  // Solver Attempts
356  emitter << YAML::Key << "kinematics_solver_attempts";
357  emitter << YAML::Value << group_meta_data_[group_it->name_].kinematics_solver_attempts_;
358 
359  emitter << YAML::EndMap;
360  }
361 
362  emitter << YAML::EndMap;
363 
364  std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
365  if (!output_stream.good())
366  {
367  ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
368  return false;
369  }
370 
371  output_stream << emitter.c_str();
372  output_stream.close();
373 
374  return true; // file created successfully
375 }
376 
377 // ******************************************************************************************
378 // Helper function to get the controller that is controlling the joint
379 // ******************************************************************************************
380 std::string MoveItConfigData::getJointHardwareInterface(const std::string& joint_name)
381 {
382  for (std::size_t i = 0; i < ros_controllers_config_.size(); ++i)
383  {
384  std::vector<std::string>::iterator joint_it =
385  std::find(ros_controllers_config_[i].joints_.begin(), ros_controllers_config_[i].joints_.end(), joint_name);
386  if (joint_it != ros_controllers_config_[i].joints_.end())
387  {
388  if (ros_controllers_config_[i].type_.substr(0, 8) == "position")
389  return "hardware_interface/PositionJointInterface";
390  else if (ros_controllers_config_[i].type_.substr(0, 8) == "velocity")
391  return "hardware_interface/VelocityJointInterface";
392  // As of writing this, available joint command interfaces are position, velocity and effort.
393  else
394  return "hardware_interface/EffortJointInterface";
395  }
396  }
397  // If the joint was not found in any controller return EffortJointInterface
398  return "hardware_interface/EffortJointInterface";
399 }
400 
401 // ******************************************************************************************
402 // Writes a Gazebo compatible robot URDF to gazebo_compatible_urdf_string_
403 // ******************************************************************************************
405 {
406  bool new_urdf_needed = false;
407  TiXmlDocument urdf_document;
408 
409  // Used to convert XmlDocument to std string
410  TiXmlPrinter printer;
411  urdf_document.Parse((const char*)urdf_string_.c_str(), 0, TIXML_ENCODING_UTF8);
412  try
413  {
414  for (TiXmlElement* doc_element = urdf_document.RootElement()->FirstChildElement(); doc_element != NULL;
415  doc_element = doc_element->NextSiblingElement())
416  {
417  if (static_cast<std::string>(doc_element->Value()).find("link") != std::string::npos)
418  {
419  // Before adding inertial elements, make sure there is none and the link has collision element
420  if (doc_element->FirstChildElement("inertial") == NULL && doc_element->FirstChildElement("collision") != NULL)
421  {
422  new_urdf_needed = true;
423  TiXmlElement inertia_link("inertial");
424  TiXmlElement mass("mass");
425  TiXmlElement inertia_joint("inertia");
426 
427  mass.SetAttribute("value", "0.1");
428 
429  inertia_joint.SetAttribute("ixx", "0.03");
430  inertia_joint.SetAttribute("iyy", "0.03");
431  inertia_joint.SetAttribute("izz", "0.03");
432  inertia_joint.SetAttribute("ixy", "0.0");
433  inertia_joint.SetAttribute("ixz", "0.0");
434  inertia_joint.SetAttribute("iyz", "0.0");
435 
436  inertia_link.InsertEndChild(mass);
437  inertia_link.InsertEndChild(inertia_joint);
438 
439  doc_element->InsertEndChild(inertia_link);
440  }
441  }
442  else if (static_cast<std::string>(doc_element->Value()).find("joint") != std::string::npos)
443  {
444  // Before adding a transmission element, make sure there the joint is not fixed
445  if (static_cast<std::string>(doc_element->Attribute("type")) != "fixed")
446  {
447  new_urdf_needed = true;
448  std::string joint_name = static_cast<std::string>(doc_element->Attribute("name"));
449  TiXmlElement transmission("transmission");
450  TiXmlElement type("type");
451  TiXmlElement joint("joint");
452  TiXmlElement hardwareInterface("hardwareInterface");
453  TiXmlElement actuator("actuator");
454  TiXmlElement mechanical_reduction("mechanicalReduction");
455 
456  transmission.SetAttribute("name", std::string("trans_") + joint_name);
457  joint.SetAttribute("name", joint_name);
458  actuator.SetAttribute("name", joint_name + std::string("_motor"));
459 
460  type.InsertEndChild(TiXmlText("transmission_interface/SimpleTransmission"));
461  transmission.InsertEndChild(type);
462 
463  hardwareInterface.InsertEndChild(TiXmlText(getJointHardwareInterface(joint_name).c_str()));
464  joint.InsertEndChild(hardwareInterface);
465  transmission.InsertEndChild(joint);
466 
467  mechanical_reduction.InsertEndChild(TiXmlText("1"));
468  actuator.InsertEndChild(hardwareInterface);
469  actuator.InsertEndChild(mechanical_reduction);
470  transmission.InsertEndChild(actuator);
471 
472  urdf_document.RootElement()->InsertEndChild(transmission);
473  }
474  }
475  }
476 
477  // Add gazebo_ros_control plugin which reads the transmission tags
478  TiXmlElement gazebo("gazebo");
479  TiXmlElement plugin("plugin");
480  TiXmlElement robot_namespace("robotNamespace");
481 
482  plugin.SetAttribute("name", "gazebo_ros_control");
483  plugin.SetAttribute("filename", "libgazebo_ros_control.so");
484  robot_namespace.InsertEndChild(TiXmlText(std::string("/")));
485 
486  plugin.InsertEndChild(robot_namespace);
487  gazebo.InsertEndChild(plugin);
488 
489  urdf_document.RootElement()->InsertEndChild(gazebo);
490  }
491  catch (YAML::ParserException& e) // Catch errors
492  {
493  ROS_ERROR_STREAM_NAMED("moveit_config_data", e.what());
494  return std::string("");
495  }
496 
497  if (new_urdf_needed)
498  {
499  urdf_document.Accept(&printer);
500  return std::string(printer.CStr());
501  }
502 
503  return std::string("");
504 }
505 
506 bool MoveItConfigData::outputFakeControllersYAML(const std::string& file_path)
507 {
508  YAML::Emitter emitter;
509  emitter << YAML::BeginMap;
510 
511  emitter << YAML::Key << "controller_list";
512  emitter << YAML::Value << YAML::BeginSeq;
513 
514  // Loop through groups
515  for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
516  ++group_it)
517  {
518  // Get list of associated joints
519  const robot_model::JointModelGroup* joint_model_group = getRobotModel()->getJointModelGroup(group_it->name_);
520  emitter << YAML::BeginMap;
521  const std::vector<const robot_model::JointModel*>& joint_models = joint_model_group->getActiveJointModels();
522  emitter << YAML::Key << "name";
523  emitter << YAML::Value << "fake_" + group_it->name_ + "_controller";
524  emitter << YAML::Key << "joints";
525  emitter << YAML::Value << YAML::BeginSeq;
526 
527  // Iterate through the joints
528  for (const robot_model::JointModel* joint : joint_models)
529  {
530  if (joint->isPassive() || joint->getMimic() != NULL || joint->getType() == robot_model::JointModel::FIXED)
531  continue;
532  emitter << joint->getName();
533  }
534  emitter << YAML::EndSeq;
535  emitter << YAML::EndMap;
536  }
537  emitter << YAML::EndSeq;
538  emitter << YAML::EndMap;
539 
540  std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
541  if (!output_stream.good())
542  {
543  ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
544  return false;
545  }
546 
547  output_stream << emitter.c_str();
548  output_stream.close();
549 
550  return true; // file created successfully
551 }
552 
553 std::vector<OMPLPlannerDescription> MoveItConfigData::getOMPLPlanners()
554 {
555  std::vector<OMPLPlannerDescription> planner_des;
556 
557  OMPLPlannerDescription SBL("SBL", "geometric");
558  SBL.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()");
559  planner_des.push_back(SBL);
560 
561  OMPLPlannerDescription EST("EST", "geometric");
562  EST.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()");
563  EST.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
564  planner_des.push_back(EST);
565 
566  OMPLPlannerDescription LBKPIECE("LBKPIECE", "geometric");
567  LBKPIECE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
568  "setup()");
569  LBKPIECE.addParameter("border_fraction", "0.9", "Fraction of time focused on boarder default: 0.9");
570  LBKPIECE.addParameter("min_valid_path_fraction", "0.5", "Accept partially valid moves above fraction. default: 0.5");
571  planner_des.push_back(LBKPIECE);
572 
573  OMPLPlannerDescription BKPIECE("BKPIECE", "geometric");
574  BKPIECE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
575  "setup()");
576  BKPIECE.addParameter("border_fraction", "0.9", "Fraction of time focused on boarder default: 0.9");
577  BKPIECE.addParameter("failed_expansion_score_factor", "0.5", "When extending motion fails, scale score by factor. "
578  "default: 0.5");
579  BKPIECE.addParameter("min_valid_path_fraction", "0.5", "Accept partially valid moves above fraction. default: 0.5");
580  planner_des.push_back(BKPIECE);
581 
582  OMPLPlannerDescription KPIECE("KPIECE", "geometric");
583  KPIECE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
584  "setup()");
585  KPIECE.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
586  KPIECE.addParameter("border_fraction", "0.9", "Fraction of time focused on boarder default: 0.9 (0.0,1.]");
587  KPIECE.addParameter("failed_expansion_score_factor", "0.5", "When extending motion fails, scale score by factor. "
588  "default: 0.5");
589  KPIECE.addParameter("min_valid_path_fraction", "0.5", "Accept partially valid moves above fraction. default: 0.5");
590  planner_des.push_back(KPIECE);
591 
592  OMPLPlannerDescription RRT("RRT", "geometric");
593  RRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()");
594  RRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
595  planner_des.push_back(RRT);
596 
597  OMPLPlannerDescription RRTConnect("RRTConnect", "geometric");
598  RRTConnect.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
599  "setup()");
600  planner_des.push_back(RRTConnect);
601 
602  OMPLPlannerDescription RRTstar("RRTstar", "geometric");
603  RRTstar.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
604  "setup()");
605  RRTstar.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
606  RRTstar.addParameter("delay_collision_checking", "1", "Stop collision checking as soon as C-free parent found. "
607  "default 1");
608  planner_des.push_back(RRTstar);
609 
610  OMPLPlannerDescription TRRT("TRRT", "geometric");
611  TRRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()");
612  TRRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
613  TRRT.addParameter("max_states_failed", "10", "when to start increasing temp. default: 10");
614  TRRT.addParameter("temp_change_factor", "2.0", "how much to increase or decrease temp. default: 2.0");
615  TRRT.addParameter("min_temperature", "10e-10", "lower limit of temp change. default: 10e-10");
616  TRRT.addParameter("init_temperature", "10e-6", "initial temperature. default: 10e-6");
617  TRRT.addParameter("frountier_threshold", "0.0", "dist new state to nearest neighbor to disqualify as frontier. "
618  "default: 0.0 set in setup()");
619  TRRT.addParameter("frountierNodeRatio", "0.1", "1/10, or 1 nonfrontier for every 10 frontier. default: 0.1");
620  TRRT.addParameter("k_constant", "0.0", "value used to normalize expresssion. default: 0.0 set in setup()");
621  planner_des.push_back(TRRT);
622 
623  OMPLPlannerDescription PRM("PRM", "geometric");
624  PRM.addParameter("max_nearest_neighbors", "10", "use k nearest neighbors. default: 10");
625  planner_des.push_back(PRM);
626 
627  OMPLPlannerDescription PRMstar("PRMstar", "geometric"); // no declares in code
628  planner_des.push_back(PRMstar);
629 
630  OMPLPlannerDescription FMT("FMT", "geometric");
631  FMT.addParameter("num_samples", "1000", "number of states that the planner should sample. default: 1000");
632  FMT.addParameter("radius_multiplier", "1.1", "multiplier used for the nearest neighbors search radius. default: 1.1");
633  FMT.addParameter("nearest_k", "1", "use Knearest strategy. default: 1");
634  FMT.addParameter("cache_cc", "1", "use collision checking cache. default: 1");
635  FMT.addParameter("heuristics", "0", "activate cost to go heuristics. default: 0");
636  FMT.addParameter("extended_fmt", "1", "activate the extended FMT*: adding new samples if planner does not finish "
637  "successfully. default: 1");
638  planner_des.push_back(FMT);
639 
640  OMPLPlannerDescription BFMT("BFMT", "geometric");
641  BFMT.addParameter("num_samples", "1000", "number of states that the planner should sample. default: 1000");
642  BFMT.addParameter("radius_multiplier", "1.0", "multiplier used for the nearest neighbors search radius. default: "
643  "1.0");
644  BFMT.addParameter("nearest_k", "1", "use the Knearest strategy. default: 1");
645  BFMT.addParameter("balanced", "0", "exploration strategy: balanced true expands one tree every iteration. False will "
646  "select the tree with lowest maximum cost to go. default: 1");
647  BFMT.addParameter("optimality", "1", "termination strategy: optimality true finishes when the best possible path is "
648  "found. Otherwise, the algorithm will finish when the first feasible path is "
649  "found. default: 1");
650  BFMT.addParameter("heuristics", "1", "activates cost to go heuristics. default: 1");
651  BFMT.addParameter("cache_cc", "1", "use the collision checking cache. default: 1");
652  BFMT.addParameter("extended_fmt", "1", "Activates the extended FMT*: adding new samples if planner does not finish "
653  "successfully. default: 1");
654  planner_des.push_back(BFMT);
655 
656  OMPLPlannerDescription PDST("PDST", "geometric");
657  RRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability? default: 0.05");
658  planner_des.push_back(PDST);
659 
660  OMPLPlannerDescription STRIDE("STRIDE", "geometric");
661  STRIDE.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
662  "setup()");
663  STRIDE.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
664  STRIDE.addParameter("use_projected_distance", "0", "whether nearest neighbors are computed based on distances in a "
665  "projection of the state rather distances in the state space "
666  "itself. default: 0");
667  STRIDE.addParameter("degree", "16", "desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). "
668  "default: 16");
669  STRIDE.addParameter("max_degree", "18", "max degree of a node in the GNAT. default: 12");
670  STRIDE.addParameter("min_degree", "12", "min degree of a node in the GNAT. default: 12");
671  STRIDE.addParameter("max_pts_per_leaf", "6", "max points per leaf in the GNAT. default: 6");
672  STRIDE.addParameter("estimated_dimension", "0.0", "estimated dimension of the free space. default: 0.0");
673  STRIDE.addParameter("min_valid_path_fraction", "0.2", "Accept partially valid moves above fraction. default: 0.2");
674  planner_des.push_back(STRIDE);
675 
676  OMPLPlannerDescription BiTRRT("BiTRRT", "geometric");
677  BiTRRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
678  "setup()");
679  BiTRRT.addParameter("temp_change_factor", "0.1", "how much to increase or decrease temp. default: 0.1");
680  BiTRRT.addParameter("init_temperature", "100", "initial temperature. default: 100");
681  BiTRRT.addParameter("frountier_threshold", "0.0", "dist new state to nearest neighbor to disqualify as frontier. "
682  "default: 0.0 set in setup()");
683  BiTRRT.addParameter("frountier_node_ratio", "0.1", "1/10, or 1 nonfrontier for every 10 frontier. default: 0.1");
684  BiTRRT.addParameter("cost_threshold", "1e300", "the cost threshold. Any motion cost that is not better will not be "
685  "expanded. default: inf");
686  planner_des.push_back(BiTRRT);
687 
688  OMPLPlannerDescription LBTRRT("LBTRRT", "geometric");
689  LBTRRT.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
690  "setup()");
691  LBTRRT.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
692  LBTRRT.addParameter("epsilon", "0.4", "optimality approximation factor. default: 0.4");
693  planner_des.push_back(LBTRRT);
694 
695  OMPLPlannerDescription BiEST("BiEST", "geometric");
696  BiEST.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
697  "setup()");
698  planner_des.push_back(BiEST);
699 
700  OMPLPlannerDescription ProjEST("ProjEST", "geometric");
701  ProjEST.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
702  "setup()");
703  ProjEST.addParameter("goal_bias", "0.05", "When close to goal select goal, with this probability. default: 0.05");
704  planner_des.push_back(ProjEST);
705 
706  OMPLPlannerDescription LazyPRM("LazyPRM", "geometric");
707  LazyPRM.addParameter("range", "0.0", "Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on "
708  "setup()");
709  planner_des.push_back(LazyPRM);
710 
711  OMPLPlannerDescription LazyPRMstar("LazyPRMstar", "geometric"); // no declares in code
712  planner_des.push_back(LazyPRMstar);
713 
714  OMPLPlannerDescription SPARS("SPARS", "geometric");
715  SPARS.addParameter("stretch_factor", "3.0", "roadmap spanner stretch factor. multiplicative upper bound on path "
716  "quality. It does not make sense to make this parameter more than 3. "
717  "default: 3.0");
718  SPARS.addParameter("sparse_delta_fraction", "0.25", "delta fraction for connection distance. This value represents "
719  "the visibility range of sparse samples. default: 0.25");
720  SPARS.addParameter("dense_delta_fraction", "0.001", "delta fraction for interface detection. default: 0.001");
721  SPARS.addParameter("max_failures", "1000", "maximum consecutive failure limit. default: 1000");
722  planner_des.push_back(SPARS);
723 
724  OMPLPlannerDescription SPARStwo("SPARStwo", "geometric");
725  SPARStwo.addParameter("stretch_factor", "3.0", "roadmap spanner stretch factor. multiplicative upper bound on path "
726  "quality. It does not make sense to make this parameter more than 3. "
727  "default: 3.0");
728  SPARStwo.addParameter("sparse_delta_fraction", "0.25",
729  "delta fraction for connection distance. This value represents "
730  "the visibility range of sparse samples. default: 0.25");
731  SPARStwo.addParameter("dense_delta_fraction", "0.001", "delta fraction for interface detection. default: 0.001");
732  SPARStwo.addParameter("max_failures", "5000", "maximum consecutive failure limit. default: 5000");
733  planner_des.push_back(SPARStwo);
734 
735  return planner_des;
736 }
737 
738 // ******************************************************************************************
739 // Helper function to write the FollowJointTrajectory for each planning group to ros_controller.yaml,
740 // and erases the controller that have been written, to avoid mixing between FollowJointTrajectory
741 // which are published under the namespace of 'controller_list' and other types of controllers.
742 // ******************************************************************************************
744  std::vector<ROSControlConfig>& ros_controllers_config_output)
745 {
746  // Write default controllers
747  emitter << YAML::Key << "controller_list";
748  emitter << YAML::Value << YAML::BeginSeq;
749  {
750  for (std::vector<ROSControlConfig>::iterator controller_it = ros_controllers_config_output.begin();
751  controller_it != ros_controllers_config_output.end();)
752  {
753  // Depending on the controller type, fill the required data
754  if (controller_it->type_ == "FollowJointTrajectory")
755  {
756  emitter << YAML::BeginMap;
757  emitter << YAML::Key << "name";
758  emitter << YAML::Value << controller_it->name_;
759  emitter << YAML::Key << "action_ns";
760  emitter << YAML::Value << "follow_joint_trajectory";
761  emitter << YAML::Key << "default";
762  emitter << YAML::Value << "True";
763  emitter << YAML::Key << "type";
764  emitter << YAML::Value << controller_it->type_;
765  // Write joints
766  emitter << YAML::Key << "joints";
767  {
768  if (controller_it->joints_.size() != 1)
769  {
770  emitter << YAML::Value << YAML::BeginSeq;
771 
772  // Iterate through the joints
773  for (std::vector<std::string>::iterator joint_it = controller_it->joints_.begin();
774  joint_it != controller_it->joints_.end(); ++joint_it)
775  {
776  emitter << *joint_it;
777  }
778  emitter << YAML::EndSeq;
779  }
780  else
781  {
782  emitter << YAML::Value << YAML::BeginMap;
783  emitter << controller_it->joints_[0];
784  emitter << YAML::EndMap;
785  }
786  }
787  ros_controllers_config_output.erase(controller_it);
788  emitter << YAML::EndMap;
789  }
790  else
791  {
792  controller_it++;
793  }
794  }
795  emitter << YAML::EndSeq;
796  }
797 }
798 
799 // ******************************************************************************************
800 // Output controllers config files
801 // ******************************************************************************************
802 bool MoveItConfigData::outputROSControllersYAML(const std::string& file_path)
803 {
804  // Copy ros_control_config_ to a new vector to avoid modifying it
805  std::vector<ROSControlConfig> ros_controllers_config_output(ros_controllers_config_);
806 
807  // Cache the joints' names.
808  std::vector<std::vector<std::string>> planning_groups;
809  std::vector<std::string> group_joints;
810 
811  // We are going to write the joints names many times.
812  // Loop through groups to store the joints names in group_joints vector and reuse is.
813  for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
814  ++group_it)
815  {
816  // Get list of associated joints
817  const robot_model::JointModelGroup* joint_model_group = getRobotModel()->getJointModelGroup(group_it->name_);
818  const std::vector<const robot_model::JointModel*>& joint_models = joint_model_group->getActiveJointModels();
819  // Iterate through the joints and push into group_joints vector.
820  for (const robot_model::JointModel* joint : joint_models)
821  {
822  if (joint->isPassive() || joint->getMimic() != NULL || joint->getType() == robot_model::JointModel::FIXED)
823  continue;
824  else
825  group_joints.push_back(joint->getName());
826  }
827  // Push all the group joints into planning_groups vector.
828  planning_groups.push_back(group_joints);
829  group_joints.clear();
830  }
831 
832  YAML::Emitter emitter;
833  emitter << YAML::BeginMap;
834 
835  {
836  emitter << YAML::Comment("MoveIt-specific simulation settings");
837  emitter << YAML::Key << "moveit_sim_hw_interface" << YAML::Value << YAML::BeginMap;
838  // Moveit Simulation Controller settings for setting initial pose
839  {
840  emitter << YAML::Key << "joint_model_group";
841  emitter << YAML::Value << "controllers_initial_group_";
842  emitter << YAML::Key << "joint_model_group_pose";
843  emitter << YAML::Value << "controllers_initial_pose_";
844  emitter << YAML::EndMap;
845  }
846  // Settings for ros_control control loop
847  emitter << YAML::Newline;
848  emitter << YAML::Comment("Settings for ros_control control loop");
849  emitter << YAML::Key << "generic_hw_control_loop" << YAML::Value << YAML::BeginMap;
850  {
851  emitter << YAML::Key << "loop_hz";
852  emitter << YAML::Value << "300";
853  emitter << YAML::Key << "cycle_time_error_threshold";
854  emitter << YAML::Value << "0.01";
855  emitter << YAML::EndMap;
856  }
857  // Settings for ros_control hardware interface
858  emitter << YAML::Newline;
859  emitter << YAML::Comment("Settings for ros_control hardware interface");
860  emitter << YAML::Key << "hardware_interface" << YAML::Value << YAML::BeginMap;
861  {
862  // Get list of all joints for the robot
863  const std::vector<const robot_model::JointModel*>& joint_models = getRobotModel()->getJointModels();
864 
865  emitter << YAML::Key << "joints";
866  {
867  if (joint_models.size() != 1)
868  {
869  emitter << YAML::Value << YAML::BeginSeq;
870  // Iterate through the joints
871  for (std::vector<const robot_model::JointModel*>::const_iterator joint_it = joint_models.begin();
872  joint_it < joint_models.end(); ++joint_it)
873  {
874  if ((*joint_it)->isPassive() || (*joint_it)->getMimic() != NULL ||
875  (*joint_it)->getType() == robot_model::JointModel::FIXED)
876  continue;
877  else
878  emitter << (*joint_it)->getName();
879  }
880  emitter << YAML::EndSeq;
881  }
882  else
883  {
884  emitter << YAML::Value << YAML::BeginMap;
885  emitter << joint_models[0]->getName();
886  emitter << YAML::EndMap;
887  }
888  }
889  emitter << YAML::Key << "sim_control_mode";
890  emitter << YAML::Value << "1";
891  emitter << YAML::Comment("0: position, 1: velocity");
892  emitter << YAML::Newline;
893  emitter << YAML::EndMap;
894  }
895  // Joint State Controller
896  emitter << YAML::Comment("Publish all joint states");
897  emitter << YAML::Newline << YAML::Comment("Creates the /joint_states topic necessary in ROS");
898  emitter << YAML::Key << "joint_state_controller" << YAML::Value << YAML::BeginMap;
899  {
900  emitter << YAML::Key << "type";
901  emitter << YAML::Value << "joint_state_controller/JointStateController";
902  emitter << YAML::Key << "publish_rate";
903  emitter << YAML::Value << "50";
904  emitter << YAML::EndMap;
905  }
906 
907  // Writes Follow Joint Trajectory ROS controllers to ros_controller.yaml
908  outputFollowJointTrajectoryYAML(emitter, ros_controllers_config_output);
909 
910  for (std::vector<ROSControlConfig>::const_iterator controller_it = ros_controllers_config_output.begin();
911  controller_it != ros_controllers_config_output.end(); ++controller_it)
912  {
913  emitter << YAML::Key << controller_it->name_;
914  emitter << YAML::Value << YAML::BeginMap;
915  emitter << YAML::Key << "type";
916  emitter << YAML::Value << controller_it->type_;
917 
918  // Write joints
919  emitter << YAML::Key << "joints";
920  {
921  if (controller_it->joints_.size() != 1)
922  {
923  emitter << YAML::Value << YAML::BeginSeq;
924 
925  // Iterate through the joints
926  for (std::vector<std::string>::const_iterator joint_it = controller_it->joints_.begin();
927  joint_it != controller_it->joints_.end(); ++joint_it)
928  {
929  emitter << *joint_it;
930  }
931  emitter << YAML::EndSeq;
932  }
933  else
934  {
935  emitter << YAML::Value << YAML::BeginMap;
936  emitter << controller_it->joints_[0];
937  emitter << YAML::EndMap;
938  }
939  }
940  // Write gains as they are required for vel and effort controllers
941  emitter << YAML::Key << "gains";
942  emitter << YAML::Value << YAML::BeginMap;
943  {
944  // Iterate through the joints
945  for (std::vector<std::string>::const_iterator joint_it = controller_it->joints_.begin();
946  joint_it != controller_it->joints_.end(); ++joint_it)
947  {
948  emitter << YAML::Key << *joint_it << YAML::Value << YAML::BeginMap;
949  emitter << YAML::Key << "p";
950  emitter << YAML::Value << "100";
951  emitter << YAML::Key << "d";
952  emitter << YAML::Value << "1";
953  emitter << YAML::Key << "i";
954  emitter << YAML::Value << "1";
955  emitter << YAML::Key << "i_clamp";
956  emitter << YAML::Value << "1" << YAML::EndMap;
957  }
958  emitter << YAML::EndMap;
959  }
960  emitter << YAML::EndMap;
961  }
962  }
963 
964  std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
965  if (!output_stream.good())
966  {
967  ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
968  return false;
969  }
970  output_stream << emitter.c_str();
971  output_stream.close();
972 
973  return true; // file created successfully
974 }
975 
976 // ******************************************************************************************
977 // Output 3D Sensor configuration file
978 // ******************************************************************************************
979 bool MoveItConfigData::output3DSensorPluginYAML(const std::string& file_path)
980 {
981  YAML::Emitter emitter;
982  emitter << YAML::BeginMap;
983 
984  emitter << YAML::Comment("The name of this file shouldn't be changed, or else the Setup Assistant won't detect it");
985  emitter << YAML::Key << "sensors";
986  emitter << YAML::Value << YAML::BeginSeq;
987 
988  // Can we have more than one plugin config?
989  emitter << YAML::BeginMap;
990 
991  // Make sure sensors_plugin_config_parameter_list_ is not empty
993  {
994  for (auto& parameter : sensors_plugin_config_parameter_list_[0])
995  {
996  emitter << YAML::Key << parameter.first;
997  emitter << YAML::Value << parameter.second.getValue();
998  }
999  }
1000 
1001  emitter << YAML::EndMap;
1002 
1003  emitter << YAML::EndSeq;
1004 
1005  emitter << YAML::EndMap;
1006 
1007  std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
1008  if (!output_stream.good())
1009  {
1010  ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
1011  return false;
1012  }
1013 
1014  output_stream << emitter.c_str();
1015  output_stream.close();
1016 
1017  return true; // file created successfully
1018 }
1019 
1020 // ******************************************************************************************
1021 // Output joint limits config files
1022 // ******************************************************************************************
1023 bool MoveItConfigData::outputJointLimitsYAML(const std::string& file_path)
1024 {
1025  YAML::Emitter emitter;
1026  emitter << YAML::BeginMap;
1027 
1028  emitter << YAML::Key << "joint_limits";
1029  emitter << YAML::Value << YAML::BeginMap;
1030 
1031  // Union all the joints in groups. Uses a custom comparator to allow the joints to be sorted by name
1032  std::set<const robot_model::JointModel*, joint_model_compare> joints;
1033 
1034  // Loop through groups
1035  for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
1036  ++group_it)
1037  {
1038  // Get list of associated joints
1039  const robot_model::JointModelGroup* joint_model_group = getRobotModel()->getJointModelGroup(group_it->name_);
1040 
1041  const std::vector<const robot_model::JointModel*>& joint_models = joint_model_group->getJointModels();
1042 
1043  // Iterate through the joints
1044  for (std::vector<const robot_model::JointModel*>::const_iterator joint_it = joint_models.begin();
1045  joint_it != joint_models.end(); ++joint_it)
1046  {
1047  // Check that this joint only represents 1 variable.
1048  if ((*joint_it)->getVariableCount() == 1)
1049  joints.insert(*joint_it);
1050  }
1051  }
1052 
1053  // Add joints to yaml file, if no more than 1 dof
1054  for (std::set<const robot_model::JointModel*>::iterator joint_it = joints.begin(); joint_it != joints.end();
1055  ++joint_it)
1056  {
1057  emitter << YAML::Key << (*joint_it)->getName();
1058  emitter << YAML::Value << YAML::BeginMap;
1059 
1060  const robot_model::VariableBounds& b = (*joint_it)->getVariableBounds()[0];
1061 
1062  // Output property
1063  emitter << YAML::Key << "has_velocity_limits";
1064  if (b.velocity_bounded_)
1065  emitter << YAML::Value << "true";
1066  else
1067  emitter << YAML::Value << "false";
1068 
1069  // Output property
1070  emitter << YAML::Key << "max_velocity";
1071  emitter << YAML::Value << std::min(fabs(b.max_velocity_), fabs(b.min_velocity_));
1072 
1073  // Output property
1074  emitter << YAML::Key << "has_acceleration_limits";
1075  if (b.acceleration_bounded_)
1076  emitter << YAML::Value << "true";
1077  else
1078  emitter << YAML::Value << "false";
1079 
1080  // Output property
1081  emitter << YAML::Key << "max_acceleration";
1082  emitter << YAML::Value << std::min(fabs(b.max_acceleration_), fabs(b.min_acceleration_));
1083 
1084  emitter << YAML::EndMap;
1085  }
1086 
1087  emitter << YAML::EndMap;
1088 
1089  std::ofstream output_stream(file_path.c_str(), std::ios_base::trunc);
1090  if (!output_stream.good())
1091  {
1092  ROS_ERROR_STREAM("Unable to open file for writing " << file_path);
1093  return false;
1094  }
1095  // Add documentation into joint_limits.yaml
1096  output_stream << "# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or "
1097  "augmented as needed"
1098  << std::endl;
1099  output_stream << "# Specific joint properties can be changed with the keys [max_position, min_position, "
1100  "max_velocity, max_acceleration]"
1101  << std::endl;
1102  output_stream << "# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]" << std::endl;
1103  output_stream << emitter.c_str();
1104  output_stream.close();
1105 
1106  return true; // file created successfully
1107 }
1108 
1109 // ******************************************************************************************
1110 // Set list of collision link pairs in SRDF; sorted; with optional filter
1111 // ******************************************************************************************
1112 
1114 {
1115 public:
1117  : dc_(dc), key_(dc.link1_ < dc.link2_ ? (dc.link1_ + "|" + dc.link2_) : (dc.link2_ + "|" + dc.link1_))
1118  {
1119  }
1120  operator const srdf::Model::DisabledCollision&() const
1121  {
1122  return dc_;
1123  }
1124  bool operator<(const SortableDisabledCollision& other) const
1125  {
1126  return key_ < other.key_;
1127  }
1128 
1129 private:
1131  const std::string key_;
1132 };
1133 
1135 {
1136  // Create temp disabled collision
1138 
1139  std::set<SortableDisabledCollision> disabled_collisions;
1140  disabled_collisions.insert(srdf_->disabled_collisions_.begin(), srdf_->disabled_collisions_.end());
1141 
1142  // copy the data in this class's LinkPairMap datastructure to srdf::Model::DisabledCollision format
1143  for (moveit_setup_assistant::LinkPairMap::const_iterator pair_it = link_pairs.begin(); pair_it != link_pairs.end();
1144  ++pair_it)
1145  {
1146  // Only copy those that are actually disabled
1147  if (pair_it->second.disable_check)
1148  {
1149  if ((1 << pair_it->second.reason) & skip_mask)
1150  continue;
1151 
1152  dc.link1_ = pair_it->first.first;
1153  dc.link2_ = pair_it->first.second;
1154  dc.reason_ = moveit_setup_assistant::disabledReasonToString(pair_it->second.reason);
1155 
1156  disabled_collisions.insert(SortableDisabledCollision(dc));
1157  }
1158  }
1159 
1160  srdf_->disabled_collisions_.assign(disabled_collisions.begin(), disabled_collisions.end());
1161 }
1162 
1163 // ******************************************************************************************
1164 // Decide the best two joints to be used for the projection evaluator
1165 // ******************************************************************************************
1166 std::string MoveItConfigData::decideProjectionJoints(std::string planning_group)
1167 {
1168  std::string joint_pair = "";
1169 
1170  // Retrieve pointer to the shared kinematic model
1171  const robot_model::RobotModelConstPtr& model = getRobotModel();
1172 
1173  // Error check
1174  if (!model->hasJointModelGroup(planning_group))
1175  return joint_pair;
1176 
1177  // Get the joint model group
1178  const robot_model::JointModelGroup* group = model->getJointModelGroup(planning_group);
1179 
1180  // get vector of joint names
1181  const std::vector<std::string> joints = group->getJointModelNames();
1182 
1183  if (joints.size() >= 2)
1184  {
1185  // Check that the first two joints have only 1 variable
1186  if (group->getJointModel(joints[0])->getVariableCount() == 1 &&
1187  group->getJointModel(joints[1])->getVariableCount() == 1)
1188  {
1189  // Just choose the first two joints.
1190  joint_pair = "joints(" + joints[0] + "," + joints[1] + ")";
1191  }
1192  }
1193 
1194  return joint_pair;
1195 }
1196 
1197 template <typename T>
1198 bool parse(const YAML::Node& node, const std::string& key, T& storage, const T& default_value = T())
1199 {
1200  const YAML::Node& n = node[key];
1201  bool valid = n;
1202  storage = valid ? n.as<T>() : default_value;
1203  return valid;
1204 }
1205 
1206 bool MoveItConfigData::inputOMPLYAML(const std::string& file_path)
1207 {
1208  // Load file
1209  std::ifstream input_stream(file_path.c_str());
1210  if (!input_stream.good())
1211  {
1212  ROS_ERROR_STREAM("Unable to open file for reading " << file_path);
1213  return false;
1214  }
1215 
1216  // Begin parsing
1217  try
1218  {
1219  YAML::Node doc = YAML::Load(input_stream);
1220 
1221  // Loop through all groups
1222  for (YAML::const_iterator group_it = doc.begin(); group_it != doc.end(); ++group_it)
1223  {
1224  // get group name
1225  const std::string group_name = group_it->first.as<std::string>();
1226 
1227  // compare group name found to list of groups in group_meta_data_
1228  std::map<std::string, GroupMetaData>::iterator group_meta_it;
1229  group_meta_it = group_meta_data_.find(group_name);
1230  if (group_meta_it != group_meta_data_.end())
1231  {
1232  std::string planner;
1233  parse(group_it->second, "default_planner_config", planner);
1234  std::size_t pos = planner.find("kConfigDefault");
1235  if (pos != std::string::npos)
1236  {
1237  planner = planner.substr(0, pos);
1238  }
1239  group_meta_data_[group_name].default_planner_ = planner;
1240  }
1241  }
1242  }
1243  catch (YAML::ParserException& e) // Catch errors
1244  {
1245  ROS_ERROR_STREAM(e.what());
1246  return false;
1247  }
1248  return true;
1249 }
1250 
1251 // ******************************************************************************************
1252 // Input kinematics.yaml file
1253 // ******************************************************************************************
1254 bool MoveItConfigData::inputKinematicsYAML(const std::string& file_path)
1255 {
1256  // Load file
1257  std::ifstream input_stream(file_path.c_str());
1258  if (!input_stream.good())
1259  {
1260  ROS_ERROR_STREAM("Unable to open file for reading " << file_path);
1261  return false;
1262  }
1263 
1264  // Begin parsing
1265  try
1266  {
1267  YAML::Node doc = YAML::Load(input_stream);
1268 
1269  // Loop through all groups
1270  for (YAML::const_iterator group_it = doc.begin(); group_it != doc.end(); ++group_it)
1271  {
1272  const std::string& group_name = group_it->first.as<std::string>();
1273  const YAML::Node& group = group_it->second;
1274 
1275  // Create new meta data
1276  GroupMetaData meta_data;
1277 
1278  parse(group, "kinematics_solver", meta_data.kinematics_solver_);
1279  parse(group, "kinematics_solver_search_resolution", meta_data.kinematics_solver_search_resolution_,
1281  parse(group, "kinematics_solver_timeout", meta_data.kinematics_solver_timeout_, DEFAULT_KIN_SOLVER_TIMEOUT_);
1282  parse(group, "kinematics_solver_attempts", meta_data.kinematics_solver_attempts_, DEFAULT_KIN_SOLVER_ATTEMPTS_);
1283 
1284  // Assign meta data to vector
1285  group_meta_data_[group_name] = meta_data;
1286  }
1287  }
1288  catch (YAML::ParserException& e) // Catch errors
1289  {
1290  ROS_ERROR_STREAM(e.what());
1291  return false;
1292  }
1293 
1294  return true; // file created successfully
1295 }
1296 
1297 // ******************************************************************************************
1298 // Helper function for parsing an individual ROSController from ros_controllers yaml file
1299 // ******************************************************************************************
1300 bool MoveItConfigData::parseROSController(const YAML::Node& controller)
1301 {
1302  // Used in parsing ROS controllers
1303  ROSControlConfig control_setting;
1304 
1305  if (const YAML::Node& trajectory_controllers = controller)
1306  {
1307  for (std::size_t trajectory_id = 0; trajectory_id < trajectory_controllers.size(); ++trajectory_id)
1308  {
1309  // Controller node
1310  if (const YAML::Node& controller_node = trajectory_controllers[trajectory_id])
1311  {
1312  if (const YAML::Node& joints = controller_node["joints"])
1313  {
1314  control_setting.joints_.clear();
1315  for (YAML::const_iterator joint_it = joints.begin(); joint_it != joints.end(); ++joint_it)
1316  {
1317  control_setting.joints_.push_back(joint_it->as<std::string>());
1318  }
1319  if (!parse(controller_node, "name", control_setting.name_))
1320  {
1321  ROS_ERROR_STREAM_NAMED("ros_controller.yaml", "Couldn't parse ros_controllers.yaml");
1322  return false;
1323  }
1324  if (!parse(controller_node, "type", control_setting.type_))
1325  {
1326  ROS_ERROR_STREAM_NAMED("ros_controller.yaml", "Couldn't parse ros_controllers.yaml");
1327  return false;
1328  }
1329  // All required fields were parsed correctly
1330  ros_controllers_config_.push_back(control_setting);
1331  }
1332  else
1333  {
1334  ROS_ERROR_STREAM_NAMED("ros_controller.yaml", "Couldn't parse ros_controllers.yaml");
1335  return false;
1336  }
1337  }
1338  }
1339  }
1340  return true;
1341 }
1342 
1343 // ******************************************************************************************
1344 // Helper function for parsing ROSControllers from ros_controllers yaml file
1345 // ******************************************************************************************
1346 bool MoveItConfigData::processROSControllers(std::ifstream& input_stream)
1347 {
1348  // Used in parsing ROS controllers
1349  ROSControlConfig control_setting;
1350  YAML::Node controllers = YAML::Load(input_stream);
1351 
1352  // Loop through all controllers
1353  for (YAML::const_iterator controller_it = controllers.begin(); controller_it != controllers.end(); ++controller_it)
1354  {
1355  // Follow Joint Trajectory action controllers
1356  if (controller_it->first.as<std::string>() == "controller_list")
1357  {
1358  if (!parseROSController(controller_it->second))
1359  return false;
1360  }
1361  // Other settings found in the ros_controllers file
1362  else
1363  {
1364  const std::string& controller_name = controller_it->first.as<std::string>();
1365  control_setting.joints_.clear();
1366 
1367  // Push joints if found in the controller
1368  if (const YAML::Node& joints = controller_it->second["joints"])
1369  {
1370  if (joints.IsSequence())
1371  {
1372  for (YAML::const_iterator joint_it = joints.begin(); joint_it != joints.end(); ++joint_it)
1373  {
1374  control_setting.joints_.push_back(joint_it->as<std::string>());
1375  }
1376  }
1377  else
1378  {
1379  control_setting.joints_.push_back(joints.as<std::string>());
1380  }
1381  }
1382 
1383  // If the setting has joints then it is a controller that needs to be parsed
1384  if (!control_setting.joints_.empty())
1385  {
1386  if (const YAML::Node& urdf_node = controller_it->second["type"])
1387  {
1388  control_setting.type_ = controller_it->second["type"].as<std::string>();
1389  control_setting.name_ = controller_name;
1390  ros_controllers_config_.push_back(control_setting);
1391  control_setting.joints_.clear();
1392  }
1393  }
1394  }
1395  }
1396  return true;
1397 }
1398 
1399 // ******************************************************************************************
1400 // Input ros_controllers.yaml file
1401 // ******************************************************************************************
1402 bool MoveItConfigData::inputROSControllersYAML(const std::string& file_path)
1403 {
1404  // Load file
1405  std::ifstream input_stream(file_path.c_str());
1406  if (!input_stream.good())
1407  {
1408  ROS_WARN_STREAM_NAMED("ros_controllers.yaml", "Does not exist " << file_path);
1409  return false;
1410  }
1411 
1412  // Begin parsing
1413  try
1414  {
1415  processROSControllers(input_stream);
1416  }
1417  catch (YAML::ParserException& e) // Catch errors
1418  {
1419  ROS_ERROR_STREAM(e.what());
1420  return false;
1421  }
1422 
1423  return true; // file read successfully
1424 }
1425 
1426 // ******************************************************************************************
1427 // Add a Follow Joint Trajectory action Controller for each Planning Group
1428 // ******************************************************************************************
1430 {
1431  if (srdf_->srdf_model_->getGroups().size() == 0)
1432  return false;
1433  // Loop through groups
1434  for (std::vector<srdf::Model::Group>::const_iterator group_it = srdf_->srdf_model_->getGroups().begin();
1435  group_it != srdf_->srdf_model_->getGroups().end(); ++group_it)
1436  {
1437  ROSControlConfig group_controller;
1438  // Get list of associated joints
1439  const robot_model::JointModelGroup* joint_model_group = getRobotModel()->getJointModelGroup(group_it->name_);
1440  const std::vector<const robot_model::JointModel*>& joint_models = joint_model_group->getActiveJointModels();
1441 
1442  // Iterate through the joints
1443  for (const robot_model::JointModel* joint : joint_models)
1444  {
1445  if (joint->isPassive() || joint->getMimic() != NULL || joint->getType() == robot_model::JointModel::FIXED)
1446  continue;
1447  group_controller.joints_.push_back(joint->getName());
1448  }
1449  if (!group_controller.joints_.empty())
1450  {
1451  group_controller.name_ = group_it->name_ + "_controller";
1452  group_controller.type_ = "FollowJointTrajectory";
1453  addROSController(group_controller);
1454  }
1455  }
1456  return true;
1457 }
1458 
1459 // ******************************************************************************************
1460 // Set package path; try to resolve path from package name if directory does not exist
1461 // ******************************************************************************************
1462 bool MoveItConfigData::setPackagePath(const std::string& pkg_path)
1463 {
1464  std::string full_package_path;
1465 
1466  // check that the folder exists
1467  if (!fs::is_directory(pkg_path))
1468  {
1469  // does not exist, check if its a package
1470  full_package_path = ros::package::getPath(pkg_path);
1471 
1472  // check that the folder exists
1473  if (!fs::is_directory(full_package_path))
1474  {
1475  return false;
1476  }
1477  }
1478  else
1479  {
1480  // they inputted a full path
1481  full_package_path = pkg_path;
1482  }
1483 
1484  config_pkg_path_ = full_package_path;
1485  return true;
1486 }
1487 
1488 // ******************************************************************************************
1489 // Resolve path to .setup_assistant file
1490 // ******************************************************************************************
1491 
1493 {
1494  path = appendPaths(config_pkg_path_, ".setup_assistant");
1495 
1496  // Check if the old package is a setup assistant package
1497  return fs::is_regular_file(path);
1498 }
1499 
1500 // ******************************************************************************************
1501 // Make the full URDF path using the loaded .setup_assistant data
1502 // ******************************************************************************************
1504 {
1505  boost::trim(urdf_pkg_name_);
1506 
1507  // Check if a package name was provided
1508  if (urdf_pkg_name_.empty() || urdf_pkg_name_ == "\"\"")
1509  {
1511  urdf_pkg_name_.clear();
1512  }
1513  else
1514  {
1515  // Check that ROS can find the package
1516  std::string robot_desc_pkg_path = ros::package::getPath(urdf_pkg_name_);
1517 
1518  if (robot_desc_pkg_path.empty())
1519  {
1520  urdf_path_.clear();
1521  return false;
1522  }
1523 
1524  // Append the relative URDF url path
1525  urdf_path_ = appendPaths(robot_desc_pkg_path, urdf_pkg_relative_path_);
1526  }
1527 
1528  // Check that this file exits -------------------------------------------------
1529  return fs::is_regular_file(urdf_path_);
1530 }
1531 
1532 // ******************************************************************************************
1533 // Make the full SRDF path using the loaded .setup_assistant data
1534 // ******************************************************************************************
1535 bool MoveItConfigData::createFullSRDFPath(const std::string& package_path)
1536 {
1538 
1539  return fs::is_regular_file(srdf_path_);
1540 }
1541 
1542 // ******************************************************************************************
1543 // Input .setup_assistant file - contains data used for the MoveIt! Setup Assistant
1544 // ******************************************************************************************
1545 bool MoveItConfigData::inputSetupAssistantYAML(const std::string& file_path)
1546 {
1547  // Load file
1548  std::ifstream input_stream(file_path.c_str());
1549  if (!input_stream.good())
1550  {
1551  ROS_ERROR_STREAM("Unable to open file for reading " << file_path);
1552  return false;
1553  }
1554 
1555  // Begin parsing
1556  try
1557  {
1558  const YAML::Node& doc = YAML::Load(input_stream);
1559 
1560  // Get title node
1561  if (const YAML::Node& title_node = doc["moveit_setup_assistant_config"])
1562  {
1563  // URDF Properties
1564  if (const YAML::Node& urdf_node = title_node["URDF"])
1565  {
1566  if (!parse(urdf_node, "package", urdf_pkg_name_))
1567  return false; // if we do not find this value we cannot continue
1568 
1569  if (!parse(urdf_node, "relative_path", urdf_pkg_relative_path_))
1570  return false; // if we do not find this value we cannot continue
1571 
1572  parse(urdf_node, "xacro_args", xacro_args_);
1573  }
1574  // SRDF Properties
1575  if (const YAML::Node& srdf_node = title_node["SRDF"])
1576  {
1577  if (!parse(srdf_node, "relative_path", srdf_pkg_relative_path_))
1578  return false; // if we do not find this value we cannot continue
1579  }
1580  // Package generation time
1581  if (const YAML::Node& config_node = title_node["CONFIG"])
1582  {
1583  parse(config_node, "author_name", author_name_);
1584  parse(config_node, "author_email", author_email_);
1585  parse(config_node, "generated_timestamp", config_pkg_generated_timestamp_);
1586  }
1587  return true;
1588  }
1589  }
1590  catch (YAML::ParserException& e) // Catch errors
1591  {
1592  ROS_ERROR_STREAM(e.what());
1593  }
1594 
1595  return false; // if it gets to this point an error has occured
1596 }
1597 
1598 // ******************************************************************************************
1599 // Input sensors_3d yaml file
1600 // ******************************************************************************************
1601 bool MoveItConfigData::input3DSensorsYAML(const std::string& default_file_path, const std::string& file_path)
1602 {
1603  // Load default parameters file
1604  std::ifstream default_input_stream(default_file_path.c_str());
1605  if (!default_input_stream.good())
1606  {
1607  ROS_ERROR_STREAM_NAMED("sensors_3d.yaml", "Unable to open file for reading " << default_file_path);
1608  return false;
1609  }
1610 
1611  // Parse default parameters values
1612  try
1613  {
1614  const YAML::Node& doc = YAML::Load(default_input_stream);
1615 
1616  // Get sensors node
1617  if (const YAML::Node& sensors_node = doc["sensors"])
1618  {
1619  // Make sue that the sensors are written as a sequence
1620  if (sensors_node.IsSequence())
1621  {
1622  GenericParameter sensor_param;
1623  std::map<std::string, GenericParameter> sensor_map;
1624 
1625  // Loop over the sensors available in the file
1626  for (std::size_t i = 0; i < sensors_node.size(); ++i)
1627  {
1628  if (const YAML::Node& sensor_node = sensors_node[i])
1629  {
1630  for (YAML::const_iterator sensor_it = sensor_node.begin(); sensor_it != sensor_node.end(); ++sensor_it)
1631  {
1632  sensor_param.setName(sensor_it->first.as<std::string>());
1633  sensor_param.setValue(sensor_it->second.as<std::string>());
1634 
1635  // Set the key as the parameter name to make accessing it easier
1636  sensor_map[sensor_it->first.as<std::string>()] = sensor_param;
1637  }
1638  sensors_plugin_config_parameter_list_.push_back(sensor_map);
1639  }
1640  }
1641  }
1642  }
1643  }
1644  catch (YAML::ParserException& e) // Catch errors
1645  {
1646  ROS_ERROR_STREAM("Error parsing default sensors yaml: " << e.what());
1647  }
1648 
1649  // Is there a sensors config in the package?
1650  if (file_path.empty())
1651  {
1652  return true;
1653  }
1654 
1655  // Load file
1656  std::ifstream input_stream(file_path.c_str());
1657  if (!input_stream.good())
1658  {
1659  ROS_ERROR_STREAM_NAMED("sensors_3d.yaml", "Unable to open file for reading " << file_path);
1660  return false;
1661  }
1662 
1663  // Begin parsing
1664  try
1665  {
1666  const YAML::Node& doc = YAML::Load(input_stream);
1667  // Get sensors node
1668  const YAML::Node& sensors_node = doc["sensors"];
1669 
1670  // Make sure that the sensors are written as a sequence
1671  if (sensors_node && sensors_node.IsSequence())
1672  {
1673  GenericParameter sensor_param;
1674  std::map<std::string, GenericParameter> sensor_map;
1675  bool empty_node = true;
1676 
1677  // Loop over the sensors available in the file
1678  for (std::size_t i = 0; i < sensors_node.size(); ++i)
1679  {
1680  if (const YAML::Node& sensor_node = sensors_node[i])
1681  {
1682  for (YAML::const_iterator sensor_it = sensor_node.begin(); sensor_it != sensor_node.end(); ++sensor_it)
1683  {
1684  empty_node = false;
1685  sensor_param.setName(sensor_it->first.as<std::string>());
1686  sensor_param.setValue(sensor_it->second.as<std::string>());
1687 
1688  // Set the key as the parameter name to make accessing it easier
1689  sensor_map[sensor_it->first.as<std::string>()] = sensor_param;
1690  }
1691  // Don't push empty nodes
1692  if (!empty_node)
1693  sensors_plugin_config_parameter_list_.push_back(sensor_map);
1694  }
1695  }
1696  }
1697  return true;
1698  }
1699  catch (YAML::ParserException& e) // Catch errors
1700  {
1701  ROS_ERROR_STREAM("Error parsing sensors yaml: " << e.what());
1702  }
1703 
1704  return false; // if it gets to this point an error has occured
1705 }
1706 
1707 // ******************************************************************************************
1708 // Helper Function for joining a file path and a file name, or two file paths, etc, in a cross-platform way
1709 // ******************************************************************************************
1710 std::string MoveItConfigData::appendPaths(const std::string& path1, const std::string& path2)
1711 {
1712  fs::path result = path1;
1713  result /= path2;
1714  return result.make_preferred().native().c_str();
1715 }
1716 
1718 {
1719  // Find the group we are editing based on the goup name string
1720  srdf::Model::Group* searched_group = NULL; // used for holding our search results
1721 
1722  for (std::vector<srdf::Model::Group>::iterator group_it = srdf_->groups_.begin(); group_it != srdf_->groups_.end();
1723  ++group_it)
1724  {
1725  if (group_it->name_ == name) // string match
1726  {
1727  searched_group = &(*group_it); // convert to pointer from iterator
1728  break; // we are done searching
1729  }
1730  }
1731 
1732  // Check if subgroup was found
1733  if (searched_group == NULL) // not found
1734  ROS_FATAL_STREAM("An internal error has occured while searching for groups. Group '" << name << "' was not found "
1735  "in the SRDF.");
1736 
1737  return searched_group;
1738 }
1739 
1740 // ******************************************************************************************
1741 // Find ROS controller by name
1742 // ******************************************************************************************
1744 {
1745  // Find the ROSController we are editing based on the ROSController name string
1746  ROSControlConfig* searched_ros_controller = NULL; // used for holding our search results
1747 
1748  for (std::vector<ROSControlConfig>::iterator controller_it = ros_controllers_config_.begin();
1749  controller_it != ros_controllers_config_.end(); ++controller_it)
1750  {
1751  if (controller_it->name_ == controller_name) // string match
1752  {
1753  searched_ros_controller = &(*controller_it); // convert to pointer from iterator
1754  break; // we are done searching
1755  }
1756  }
1757 
1758  return searched_ros_controller;
1759 }
1760 
1761 // ******************************************************************************************
1762 // Deletes a ROS controller by name
1763 // ******************************************************************************************
1764 bool MoveItConfigData::deleteROSController(const std::string& controller_name)
1765 {
1766  for (std::vector<ROSControlConfig>::iterator controller_it = ros_controllers_config_.begin();
1767  controller_it != ros_controllers_config_.end(); ++controller_it)
1768  {
1769  if (controller_it->name_ == controller_name) // string match
1770  {
1771  ros_controllers_config_.erase(controller_it);
1772  // we are done searching
1773  return true;
1774  }
1775  }
1776  return false;
1777 }
1778 
1779 // ******************************************************************************************
1780 // Adds a ROS controller to ros_controllers_config_ vector
1781 // ******************************************************************************************
1783 {
1784  // Used for holding our search results
1785  ROSControlConfig* searched_ros_controller = NULL;
1786 
1787  // Find if there is an existing controller with the same name
1788  searched_ros_controller = findROSControllerByName(new_controller.name_);
1789 
1790  if (searched_ros_controller && searched_ros_controller->type_ == new_controller.type_)
1791  return false;
1792 
1793  ros_controllers_config_.push_back(new_controller);
1794  return true;
1795 }
1796 
1797 // ******************************************************************************************
1798 // Gets ros_controllers_config_ vector
1799 // ******************************************************************************************
1800 std::vector<ROSControlConfig>& MoveItConfigData::getROSControllers()
1801 {
1802  return ros_controllers_config_;
1803 }
1804 
1805 // ******************************************************************************************
1806 // Used to add a sensor plugin configuation parameter to the sensor plugin configuration parameter list
1807 // ******************************************************************************************
1808 void MoveItConfigData::addGenericParameterToSensorPluginConfig(const std::string& name, const std::string& value,
1809  const std::string& comment)
1810 {
1811  // Use index 0 since we only write one plugin
1812  GenericParameter new_parameter;
1813  new_parameter.setName(name);
1814  new_parameter.setValue(value);
1815  sensors_plugin_config_parameter_list_[0][name] = new_parameter;
1816 }
1817 
1818 // ******************************************************************************************
1819 // Used to get sensor plugin configuration parameter list
1820 // ******************************************************************************************
1821 std::vector<std::map<std::string, GenericParameter>> MoveItConfigData::getSensorPluginConfig()
1822 {
1824 }
1825 
1826 // ******************************************************************************************
1827 // Used to clear sensor plugin configuration parameter list
1828 // ******************************************************************************************
1830 {
1831  for (std::size_t param_id = 0; param_id < sensors_plugin_config_parameter_list_.size(); ++param_id)
1832  {
1833  sensors_plugin_config_parameter_list_[param_id].clear();
1834  }
1835 }
1836 
1837 } // namespace
std::time_t config_pkg_generated_timestamp_
Timestamp when configuration package was generated, if it was previously generated.
bool addDefaultControllers()
Add a Follow Joint Trajectory action Controller for each Planning Group.
#define NULL
std::string urdf_pkg_relative_path_
Path relative to urdf package (note: this may be same as urdf_path_)
std::string getGazeboCompatibleURDF()
Parses the existing urdf and constructs a string from it with the elements required by gazebo simulat...
static const int DEFAULT_KIN_SOLVER_ATTEMPTS_
#define ROS_ERROR_STREAM_NAMED(name, args)
void setRobotModel(robot_model::RobotModelPtr robot_model)
Load a robot model.
std::string srdf_pkg_relative_path_
Path relative to loaded configuration package.
bool inputOMPLYAML(const std::string &file_path)
bool outputKinematicsYAML(const std::string &file_path)
robot_model::RobotModelPtr robot_model_
Shared kinematic model.
bool operator<(const SortableDisabledCollision &other) const
bool outputSetupAssistantFile(const std::string &file_path)
urdf::ModelSharedPtr urdf_model_
URDF robot model.
bool setPackagePath(const std::string &pkg_path)
bool inputSetupAssistantYAML(const std::string &file_path)
bool addROSController(const ROSControlConfig &new_controller)
Adds a ROS controller to ros_controllers_config_ vector.
bool createFullURDFPath()
Make the full URDF path using the loaded .setup_assistant data.
static const double DEFAULT_KIN_SOLVER_TIMEOUT_
bool outputCHOMPPlanningYAML(const std::string &file_path)
std::vector< OMPLPlannerDescription > getOMPLPlanners()
std::vector< ROSControlConfig > ros_controllers_config_
ROS Controllers config data.
bool parse(const YAML::Node &node, const std::string &key, T &storage, const T &default_value=T())
std::string decideProjectionJoints(std::string planning_group)
Decide the best two joints to be used for the projection evaluator.
group
std::vector< ROSControlConfig > & getROSControllers()
Gets ros_controllers_config_ vector.
bool outputFakeControllersYAML(const std::string &file_path)
bool output3DSensorPluginYAML(const std::string &file_path)
#define ROS_FATAL_STREAM(args)
bool input3DSensorsYAML(const std::string &default_file_path, const std::string &file_path="")
#define ROS_INFO(...)
SortableDisabledCollision(const srdf::Model::DisabledCollision &dc)
def default_value(type)
planning_scene::PlanningScenePtr getPlanningScene()
Provide a shared planning scene.
std::vector< std::map< std::string, GenericParameter > > getSensorPluginConfig()
Used for adding a sensor plugin configuation parameter to the sensor plugin configuration parameter l...
srdf::SRDFWriterPtr srdf_
SRDF Data and Writer.
std::string author_name_
Name of the author of this config.
bool deleteROSController(const std::string &controller_name)
const std::string disabledReasonToString(DisabledReason reason)
Converts a reason for disabling a link pair into a string.
void setCollisionLinkPairs(const moveit_setup_assistant::LinkPairMap &link_pairs, size_t skip_mask=0)
Set list of collision link pairs in SRDF; sorted; with optional filter.
bool outputJointLimitsYAML(const std::string &file_path)
std::map< std::string, GroupMetaData > group_meta_data_
Planning groups extra data not found in srdf but used in config files.
bool parseROSController(const YAML::Node &controller)
std::string setup_assistant_path_
Setup Assistants package&#39;s path for when we use its templates.
static const double DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION_
void clearSensorPluginConfig()
Clear the sensor plugin configuration parameter list.
std::string urdf_string_
URDF robot model string.
robot_model::RobotModelConstPtr getRobotModel()
Provide a shared kinematic model loader.
void addGenericParameterToSensorPluginConfig(const std::string &name, const std::string &value="", const std::string &comment="")
Used for adding a sensor plugin configuation prameter to the sensor plugin configuration parameter li...
ROSLIB_DECL std::string getPath(const std::string &package_name)
std::string getJointHardwareInterface(const std::string &joint_name)
Helper function to get the controller that is controlling the joint.
This class describes the OMPL planners by name, type, and parameter list, used to create the ompl_pla...
std::string srdf_path_
Full file-system path to srdf.
ROSControlConfig * findROSControllerByName(const std::string &controller_name)
std::string author_email_
Email of the author of this config.
bool outputROSControllersYAML(const std::string &file_path)
bool outputOMPLPlanningYAML(const std::string &file_path)
void setEntry(const std::string &name1, const std::string &name2, bool allowed)
bool inputKinematicsYAML(const std::string &file_path)
bool createFullSRDFPath(const std::string &package_path)
Make the full SRDF path using the loaded .setup_assistant data.
void outputFollowJointTrajectoryYAML(YAML::Emitter &emitter, std::vector< ROSControlConfig > &ros_controllers_config_output)
bool inputROSControllersYAML(const std::string &file_path)
srdf::Model::Group * findGroupByName(const std::string &name)
#define ROS_ERROR_STREAM(args)
bool debug_
Is this application in debug mode?
std::string appendPaths(const std::string &path1, const std::string &path2)
bool processROSControllers(std::ifstream &input_stream)
std::string urdf_pkg_name_
Name of package containig urdf (note: this may be empty b/c user may not have urdf in pkg) ...
std::string urdf_path_
Full file-system path to urdf.
collision_detection::AllowedCollisionMatrix allowed_collision_matrix_
Allowed collision matrix for robot poses.
void addParameter(const std::string &name, const std::string &value="", const std::string &comment="")
adds a parameter to the planner description
void updateRobotModel()
Update the Kinematic Model with latest SRDF modifications.
std::string config_pkg_path_
Loaded configuration package path - if an existing package was loaded, holds that path...
std::vector< std::map< std::string, GenericParameter > > sensors_plugin_config_parameter_list_
Sensor plugin configuration parameter list, each sensor plugin type is a map.
std::map< std::pair< std::string, std::string >, LinkPairData > LinkPairMap
LinkPairMap is an adjacency list structure containing links in string-based form. Used for disabled l...
#define ROS_WARN_STREAM_NAMED(name, args)
planning_scene::PlanningScenePtr planning_scene_
Shared planning scene.
void loadAllowedCollisionMatrix()
Load the allowed collision matrix from the SRDF&#39;s list of link pairs.


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Wed Jul 10 2019 04:04:34