moveit_config_data.h
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 
37 #ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_MOVEIT_CONFIG_DATA_
38 #define MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_MOVEIT_CONFIG_DATA_
39 
40 #include <boost/shared_ptr.hpp>
41 #include <srdfdom/model.h> // use their struct datastructures
42 #include <srdfdom/srdf_writer.h> // for writing srdf data
43 #include <urdf/model.h> // to share throughout app
44 #include <yaml-cpp/yaml.h> // outputing yaml config files
46 #include <moveit/planning_scene/planning_scene.h> // for getting kinematic model
47 #include <moveit/collision_detection/collision_matrix.h> // for figuring out if robot is in collision
49 
50 namespace moveit_setup_assistant
51 {
52 // ******************************************************************************************
53 // Constants
54 // ******************************************************************************************
55 
56 // Used for loading kinematic model
57 static const std::string ROBOT_DESCRIPTION = "robot_description";
58 static const std::string MOVEIT_ROBOT_STATE = "moveit_robot_state";
59 
60 // Default kin solver values
61 static const double DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION_ = 0.005;
62 static const double DEFAULT_KIN_SOLVER_TIMEOUT_ = 0.005;
63 static const int DEFAULT_KIN_SOLVER_ATTEMPTS_ = 3;
64 
65 // ******************************************************************************************
66 // Structs
67 // ******************************************************************************************
68 
73 {
74  std::string kinematics_solver_; // Name of kinematics plugin to use
75  double kinematics_solver_search_resolution_; // resolution to use with solver
76  double kinematics_solver_timeout_; // solver timeout
77  int kinematics_solver_attempts_; // solver attempts
78  std::string default_planner_; // Name of the default planner to use
79 };
80 
85 {
86  std::string name_; // controller name
87  std::string type_; // controller type
88  std::vector<std::string> joints_; // joints controller by this controller
89 };
90 
95 {
96  std::string name; // name of parameter
97  std::string value; // value parameter will receive (but as a string)
98  std::string comment; // comment briefly describing what this parameter does
99 };
100 
104 {
105 public:
110  OMPLPlannerDescription(const std::string& name, const std::string& type)
111  {
112  name_ = name;
113  type_ = type;
114  };
117  {
118  parameter_list_.clear();
119  };
125  void addParameter(const std::string& name, const std::string& value = "", const std::string& comment = "")
126  {
128  temp.name = name;
129  temp.value = value;
130  temp.comment = comment;
131  parameter_list_.push_back(temp);
132  }
133  std::vector<OmplPlanningParameter> parameter_list_;
134  std::string name_; // name of planner
135  std::string type_; // type of planner (geometric)
136 };
137 
142 {
143 public:
145  {
146  comment_ = "";
147  };
148 
149  void setName(std::string name)
150  {
151  name_ = name;
152  };
153  void setValue(std::string value)
154  {
155  value_ = value;
156  };
157  void setComment(std::string comment)
158  {
159  comment_ = comment;
160  };
161  std::string getName()
162  {
163  return name_;
164  };
165  std::string getValue()
166  {
167  return value_;
168  };
169  std::string getComment()
170  {
171  return comment_;
172  };
173 
174 private:
175  std::string name_; // name of parameter
176  std::string value_; // value parameter will receive (but as a string)
177  std::string comment_; // comment briefly describing what this parameter does
178 };
179 
181 
189 {
190 public:
192  ~MoveItConfigData();
193 
194  // bits of information that can be entered in Setup Assistant
196  {
197  COLLISIONS = 1 << 1,
198  VIRTUAL_JOINTS = 1 << 2,
199  GROUPS = 1 << 3,
200  GROUP_CONTENTS = 1 << 4,
201  GROUP_KINEMATICS = 1 << 5,
202  POSES = 1 << 6,
203  END_EFFECTORS = 1 << 7,
204  PASSIVE_JOINTS = 1 << 8,
205  AUTHOR_INFO = 1 << 9,
206  SENSORS_CONFIG = 1 << 10,
207  SRDF = COLLISIONS | VIRTUAL_JOINTS | GROUPS | GROUP_CONTENTS | POSES | END_EFFECTORS | PASSIVE_JOINTS
208  };
209  unsigned long changes; // bitfield of changes (composed of InformationFields)
210 
211  // All of the data needed for creating a MoveIt! Configuration Files
212 
213  // ******************************************************************************************
214  // URDF Data
215  // ******************************************************************************************
216 
218  std::string urdf_path_;
219 
221  std::string urdf_pkg_name_;
222 
225 
229  std::string xacro_args_;
230 
232  urdf::ModelSharedPtr urdf_model_;
233 
235  std::string urdf_string_;
236 
237  // ******************************************************************************************
238  // SRDF Data
239  // ******************************************************************************************
240 
242  std::string srdf_path_;
243 
246 
249 
250  // ******************************************************************************************
251  // Other Data
252  // ******************************************************************************************
253 
255  std::map<std::string, GroupMetaData> group_meta_data_;
256 
259 
261  std::string config_pkg_path_;
262 
265 
267  bool debug_;
268 
271 
274 
276  std::string author_name_;
277 
279  std::string author_email_;
280 
281  // ******************************************************************************************
282  // Public Functions
283  // ******************************************************************************************
284 
286  void setRobotModel(robot_model::RobotModelPtr robot_model);
287 
289  robot_model::RobotModelConstPtr getRobotModel();
290 
292  void updateRobotModel();
293 
295  planning_scene::PlanningScenePtr getPlanningScene();
296 
303  srdf::Model::Group* findGroupByName(const std::string& name);
304 
306  void loadAllowedCollisionMatrix();
307 
308  // ******************************************************************************************
309  // Public Functions for outputting configuration and setting files
310  // ******************************************************************************************
311  std::vector<OMPLPlannerDescription> getOMPLPlanners();
312  bool outputSetupAssistantFile(const std::string& file_path);
313  bool outputOMPLPlanningYAML(const std::string& file_path);
314  bool outputCHOMPPlanningYAML(const std::string& file_path);
315  bool outputKinematicsYAML(const std::string& file_path);
316  bool outputJointLimitsYAML(const std::string& file_path);
317  bool outputFakeControllersYAML(const std::string& file_path);
318 
324  void outputFollowJointTrajectoryYAML(YAML::Emitter& emitter,
325  std::vector<ROSControlConfig>& ros_controllers_config_output);
326 
327  bool outputROSControllersYAML(const std::string& file_path);
328  bool output3DSensorPluginYAML(const std::string& file_path);
329 
334  std::string getJointHardwareInterface(const std::string& joint_name);
335 
341  std::string getGazeboCompatibleURDF();
342 
348  void setCollisionLinkPairs(const moveit_setup_assistant::LinkPairMap& link_pairs, size_t skip_mask = 0);
349 
355  std::string decideProjectionJoints(std::string planning_group);
356 
362  bool inputOMPLYAML(const std::string& file_path);
363 
369  bool inputKinematicsYAML(const std::string& file_path);
370 
376  bool parseROSController(const YAML::Node& controller);
377 
383  bool processROSControllers(std::ifstream& input_stream);
384 
390  bool inputROSControllersYAML(const std::string& file_path);
391 
396  bool addDefaultControllers();
397 
403  bool setPackagePath(const std::string& pkg_path);
404 
410  bool getSetupAssistantYAMLPath(std::string& path);
411 
413  bool createFullURDFPath();
414 
416  bool createFullSRDFPath(const std::string& package_path);
417 
424  bool inputSetupAssistantYAML(const std::string& file_path);
425 
433  bool input3DSensorsYAML(const std::string& default_file_path, const std::string& file_path = "");
434 
443  std::string appendPaths(const std::string& path1, const std::string& path2);
444 
450  bool addROSController(const ROSControlConfig& new_controller);
451 
456  std::vector<ROSControlConfig>& getROSControllers();
457 
464  ROSControlConfig* findROSControllerByName(const std::string& controller_name);
465 
472  bool deleteROSController(const std::string& controller_name);
473 
477  void addGenericParameterToSensorPluginConfig(const std::string& name, const std::string& value = "",
478  const std::string& comment = "");
479 
483  void clearSensorPluginConfig();
484 
488  std::vector<std::map<std::string, GenericParameter> > getSensorPluginConfig();
489 
497  {
498  bool operator()(const robot_model::JointModel* jm1, const robot_model::JointModel* jm2) const
499  {
500  return jm1->getName() < jm2->getName();
501  }
502  };
503 
504 private:
505  // ******************************************************************************************
506  // Private Vars
507  // ******************************************************************************************
508 
510  std::vector<std::map<std::string, GenericParameter> > sensors_plugin_config_parameter_list_;
511 
513  robot_model::RobotModelPtr robot_model_;
514 
516  std::vector<ROSControlConfig> ros_controllers_config_;
517 
519  planning_scene::PlanningScenePtr planning_scene_;
520 };
521 
522 } // namespace
523 
524 #endif
std::time_t config_pkg_generated_timestamp_
Timestamp when configuration package was generated, if it was previously generated.
std::string urdf_pkg_relative_path_
Path relative to urdf package (note: this may be same as urdf_path_)
static const int DEFAULT_KIN_SOLVER_ATTEMPTS_
std::string srdf_pkg_relative_path_
Path relative to loaded configuration package.
std::vector< OmplPlanningParameter > parameter_list_
robot_model::RobotModelPtr robot_model_
Shared kinematic model.
urdf::ModelSharedPtr urdf_model_
URDF robot model.
static const double DEFAULT_KIN_SOLVER_TIMEOUT_
std::vector< ROSControlConfig > ros_controllers_config_
ROS Controllers config data.
srdf::SRDFWriterPtr srdf_
SRDF Data and Writer.
std::string author_name_
Name of the author of this config.
std::map< std::string, GroupMetaData > group_meta_data_
Planning groups extra data not found in srdf but used in config files.
static const std::string MOVEIT_ROBOT_STATE
MOVEIT_CLASS_FORWARD(MoveItConfigData)
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_
std::string urdf_string_
URDF robot model string.
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.
bool operator()(const robot_model::JointModel *jm1, const robot_model::JointModel *jm2) const
SRDF
std::string author_email_
Email of the author of this config.
bool urdf_from_xacro_
Flag indicating whether the URDF was loaded from .xacro format.
OMPLPlannerDescription(const std::string &name, const std::string &type)
Constructor.
This class is shared with all widgets and contains the common configuration data needed for generatin...
static const std::string ROBOT_DESCRIPTION
bool debug_
Is this application in debug mode?
Custom std::set comparator, used for sorting the joint_limits.yaml file into alphabetical order...
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
std::string template_package_path_
Location that moveit_setup_assistant stores its templates.
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...
planning_scene::PlanningScenePtr planning_scene_
Shared planning scene.


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