moveit2
The MoveIt Motion Planning Framework for ROS 2.
srdf_config.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, PickNik Robotics, 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 PickNik Robotics 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: David V. Lu!! */
36 #pragma once
37 
42 #include <moveit/planning_scene/planning_scene.h> // for getting kinematic model
43 #include <srdfdom/srdf_writer.h> // for writing srdf data
44 
45 namespace moveit_setup
46 {
47 // bits of information that can be changed in the SRDF
49 {
50  NONE = 0,
51  COLLISIONS = 1 << 1,
52  VIRTUAL_JOINTS = 1 << 2,
53  GROUPS = 1 << 3,
54  GROUP_CONTENTS = 1 << 4,
55  POSES = 1 << 5,
56  END_EFFECTORS = 1 << 6,
57  PASSIVE_JOINTS = 1 << 7,
58  OTHER = 1 << 8,
59 };
60 
61 static const std::string JOINT_LIMITS_FILE = "config/joint_limits.yaml";
62 static const std::string CARTESIAN_LIMITS_FILE = "config/pilz_cartesian_limits.yaml";
63 
64 class SRDFConfig : public SetupConfig
65 {
66 public:
67  void onInit() override;
68 
69  bool isConfigured() const override
70  {
71  return robot_model_ != nullptr;
72  }
73 
74  void loadPrevious(const std::filesystem::path& package_path, const YAML::Node& node) override;
75  YAML::Node saveToYaml() const override;
76 
78  void loadSRDFFile(const std::filesystem::path& package_path, const std::filesystem::path& relative_path);
79  void loadSRDFFile(const std::filesystem::path& srdf_file_path,
80  const std::vector<std::string>& xacro_args = std::vector<std::string>());
81 
82  moveit::core::RobotModelPtr getRobotModel() const
83  {
84  return robot_model_;
85  }
86 
88  planning_scene::PlanningScenePtr getPlanningScene();
89 
92  void updateRobotModel(long changed_information = 0L);
93 
94  std::vector<std::string> getLinkNames() const;
95 
97  {
98  srdf_.no_default_collision_links_.clear();
99  srdf_.enabled_collision_pairs_.clear();
100  srdf_.disabled_collision_pairs_.clear();
101  }
102 
103  std::vector<srdf::Model::CollisionPair>& getDisabledCollisions()
104  {
105  return srdf_.disabled_collision_pairs_;
106  }
107 
108  std::vector<srdf::Model::EndEffector>& getEndEffectors()
109  {
110  return srdf_.end_effectors_;
111  }
112 
113  std::vector<srdf::Model::Group>& getGroups()
114  {
115  return srdf_.groups_;
116  }
117 
118  std::vector<std::string> getGroupNames() const
119  {
120  std::vector<std::string> group_names;
121  for (const srdf::Model::Group& group : srdf_.groups_)
122  {
123  group_names.push_back(group.name_);
124  }
125  return group_names;
126  }
127 
128  std::vector<srdf::Model::GroupState>& getGroupStates()
129  {
130  return srdf_.group_states_;
131  }
132 
133  std::vector<srdf::Model::VirtualJoint>& getVirtualJoints()
134  {
135  return srdf_.virtual_joints_;
136  }
137 
138  std::vector<srdf::Model::PassiveJoint>& getPassiveJoints()
139  {
140  return srdf_.passive_joints_;
141  }
142 
147  std::string getChildOfJoint(const std::string& joint_name) const;
148 
149  void removePoseByName(const std::string& pose_name, const std::string& group_name);
150 
151  std::vector<std::string> getJointNames(const std::string& group_name, bool include_multi_dof = true,
152  bool include_passive = true);
153 
155  {
156  public:
157  GeneratedSRDF(const std::filesystem::path& package_path, const GeneratedTime& last_gen_time, SRDFConfig& parent)
158  : GeneratedFile(package_path, last_gen_time), parent_(parent)
159  {
160  }
161 
162  std::filesystem::path getRelativePath() const override
163  {
165  }
166 
167  std::string getDescription() const override
168  {
169  return "SRDF (<a href='http://www.ros.org/wiki/srdf'>Semantic Robot Description Format</a>) is a "
170  "representation of semantic information about robots. This format is intended to represent "
171  "information about the robot that is not in the URDF file, but it is useful for a variety of "
172  "applications. The intention is to include information that has a semantic aspect to it.";
173  }
174 
175  bool hasChanges() const override
176  {
177  return parent_.changes_ > 0;
178  }
179 
180  bool write() override
181  {
182  std::filesystem::path path = getPath();
183  createParentFolders(path);
184  return parent_.write(path);
185  }
186 
187  protected:
189  };
190 
192  {
193  public:
194  GeneratedJointLimits(const std::filesystem::path& package_path, const GeneratedTime& last_gen_time,
195  SRDFConfig& parent)
196  : YamlGeneratedFile(package_path, last_gen_time), parent_(parent)
197  {
198  }
199 
200  std::filesystem::path getRelativePath() const override
201  {
202  return JOINT_LIMITS_FILE;
203  }
204 
205  std::string getDescription() const override
206  {
207  return "Contains additional information about joints that appear in your planning groups that is not "
208  "contained in the URDF, as well as allowing you to set maximum and minimum limits for velocity "
209  "and acceleration than those contained in your URDF. This information is used by our trajectory "
210  "filtering system to assign reasonable velocities and timing for the trajectory before it is "
211  "passed to the robot's controllers.";
212  }
213 
214  bool hasChanges() const override
215  {
216  return false; // Can't be changed just yet
217  }
218 
219  bool writeYaml(YAML::Emitter& emitter) override;
220 
221  protected:
223  };
224 
226  {
227  public:
228  using TemplatedGeneratedFile::TemplatedGeneratedFile;
229 
230  std::filesystem::path getRelativePath() const override
231  {
232  return CARTESIAN_LIMITS_FILE;
233  }
234 
235  std::filesystem::path getTemplatePath() const override
236  {
237  return getSharePath("moveit_setup_framework") / "templates" / CARTESIAN_LIMITS_FILE;
238  }
239 
240  std::string getDescription() const override
241  {
242  return "Cartesian velocity for planning in the workspace."
243  "The velocity is used by pilz industrial motion planner as maximum velocity for cartesian "
244  "planning requests scaled by the velocity scaling factor of an individual planning request.";
245  }
246 
247  bool hasChanges() const override
248  {
249  return false;
250  }
251  };
252 
253  void collectFiles(const std::filesystem::path& package_path, const GeneratedTime& last_gen_time,
254  std::vector<GeneratedFilePtr>& files) override
255  {
256  files.push_back(std::make_shared<GeneratedSRDF>(package_path, last_gen_time, *this));
257  files.push_back(std::make_shared<GeneratedJointLimits>(package_path, last_gen_time, *this));
258  files.push_back(std::make_shared<GeneratedCartesianLimits>(package_path, last_gen_time));
259  }
260 
261  void collectVariables(std::vector<TemplateVariable>& variables) override;
262 
263  bool write(const std::filesystem::path& path)
264  {
265  return srdf_.writeSRDF(path);
266  }
267 
268  std::filesystem::path getPath() const
269  {
270  return srdf_path_;
271  }
272 
273  unsigned long getChangeMask() const
274  {
275  return changes_;
276  }
277 
278 protected:
279  void getRelativePath();
280  void loadURDFModel();
281 
282  // ******************************************************************************************
283  // SRDF Data
284  // ******************************************************************************************
286  std::filesystem::path srdf_path_;
287 
289  std::filesystem::path srdf_pkg_relative_path_;
290 
292  srdf::SRDFWriter srdf_;
293 
294  std::shared_ptr<urdf::Model> urdf_model_;
295 
296  moveit::core::RobotModelPtr robot_model_;
297 
299  planning_scene::PlanningScenePtr planning_scene_;
300 
301  // bitfield of changes (composed of InformationFields)
302  unsigned long changes_;
303 };
304 } // namespace moveit_setup
Container for the logic for a single file to appear in MoveIt configuration package.
std::filesystem::path getPath() const
Returns the fully qualified path to this file.
std::filesystem::path getRelativePath() const override
Returns the path relative to the configuration package root.
std::string getDescription() const override
Returns an English description of this file's purpose.
std::filesystem::path getTemplatePath() const override
Returns the full path to the template file.
bool hasChanges() const override
Returns true if this file will have changes when it is written to file.
bool hasChanges() const override
Returns true if this file will have changes when it is written to file.
std::string getDescription() const override
Returns an English description of this file's purpose.
std::filesystem::path getRelativePath() const override
Returns the path relative to the configuration package root.
GeneratedJointLimits(const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, SRDFConfig &parent)
bool writeYaml(YAML::Emitter &emitter) override
std::filesystem::path getRelativePath() const override
Returns the path relative to the configuration package root.
std::string getDescription() const override
Returns an English description of this file's purpose.
bool hasChanges() const override
Returns true if this file will have changes when it is written to file.
GeneratedSRDF(const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, SRDFConfig &parent)
bool write() override
Writes the file to disk.
void updateRobotModel(long changed_information=0L)
std::vector< srdf::Model::VirtualJoint > & getVirtualJoints()
bool isConfigured() const override
Return true if this part of the configuration is completely set up.
Definition: srdf_config.hpp:69
std::vector< srdf::Model::PassiveJoint > & getPassiveJoints()
void collectFiles(const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, std::vector< GeneratedFilePtr > &files) override
Collect the files generated by this configuration and add them to the vector.
unsigned long getChangeMask() const
srdf::SRDFWriter srdf_
SRDF Data and Writer.
planning_scene::PlanningScenePtr planning_scene_
Shared planning scene.
void removePoseByName(const std::string &pose_name, const std::string &group_name)
std::shared_ptr< urdf::Model > urdf_model_
planning_scene::PlanningScenePtr getPlanningScene()
Provide a shared planning scene.
std::filesystem::path getPath() const
bool write(const std::filesystem::path &path)
std::filesystem::path srdf_pkg_relative_path_
Path relative to loaded configuration package.
std::string getChildOfJoint(const std::string &joint_name) const
Return the name of the child link of a joint.
moveit::core::RobotModelPtr getRobotModel() const
Definition: srdf_config.hpp:82
moveit::core::RobotModelPtr robot_model_
std::vector< std::string > getJointNames(const std::string &group_name, bool include_multi_dof=true, bool include_passive=true)
std::filesystem::path srdf_path_
Full file-system path to srdf.
std::vector< srdf::Model::CollisionPair > & getDisabledCollisions()
void loadSRDFFile(const std::filesystem::path &package_path, const std::filesystem::path &relative_path)
Load SRDF File.
Definition: srdf_config.cpp:76
YAML::Node saveToYaml() const override
Optionally save "meta" information for saving in the .setup_assistant yaml file.
Definition: srdf_config.cpp:56
std::vector< srdf::Model::EndEffector > & getEndEffectors()
std::vector< std::string > getGroupNames() const
void onInit() override
Overridable initialization method.
Definition: srdf_config.cpp:41
std::vector< srdf::Model::GroupState > & getGroupStates()
std::vector< std::string > getLinkNames() const
void collectVariables(std::vector< TemplateVariable > &variables) override
Collect key/value pairs for use in templates.
std::vector< srdf::Model::Group > & getGroups()
void loadPrevious(const std::filesystem::path &package_path, const YAML::Node &node) override
Loads the configuration from an existing MoveIt configuration.
Definition: srdf_config.cpp:47
where all the data for each part of the configuration is stored.
Definition: config.hpp:58
Specialization of GeneratedFile for generating a text file from a template.
Definition: templates.hpp:60
std::filesystem::path getSharePath(const std::string &package_name)
Return a path for the given package's share folder.
Definition: utilities.hpp:51
bool createParentFolders(const std::filesystem::path &file_path)
Create parent folders (recursively)
Definition: utilities.hpp:76
std::filesystem::file_time_type GeneratedTime