moveit2
The MoveIt Motion Planning Framework for ROS 2.
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Pages
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.hpp> // 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  group_names.reserve(srdf_.groups_.size());
122  for (const srdf::Model::Group& group : srdf_.groups_)
123  {
124  group_names.push_back(group.name_);
125  }
126  return group_names;
127  }
128 
129  std::vector<srdf::Model::GroupState>& getGroupStates()
130  {
131  return srdf_.group_states_;
132  }
133 
134  std::vector<srdf::Model::VirtualJoint>& getVirtualJoints()
135  {
136  return srdf_.virtual_joints_;
137  }
138 
139  std::vector<srdf::Model::PassiveJoint>& getPassiveJoints()
140  {
141  return srdf_.passive_joints_;
142  }
143 
148  std::string getChildOfJoint(const std::string& joint_name) const;
149 
150  void removePoseByName(const std::string& pose_name, const std::string& group_name);
151 
152  std::vector<std::string> getJointNames(const std::string& group_name, bool include_multi_dof = true,
153  bool include_passive = true);
154 
156  {
157  public:
158  GeneratedSRDF(const std::filesystem::path& package_path, const GeneratedTime& last_gen_time, SRDFConfig& parent)
159  : GeneratedFile(package_path, last_gen_time), parent_(parent)
160  {
161  }
162 
163  std::filesystem::path getRelativePath() const override
164  {
166  }
167 
168  std::string getDescription() const override
169  {
170  return "SRDF (<a href='http://www.ros.org/wiki/srdf'>Semantic Robot Description Format</a>) is a "
171  "representation of semantic information about robots. This format is intended to represent "
172  "information about the robot that is not in the URDF file, but it is useful for a variety of "
173  "applications. The intention is to include information that has a semantic aspect to it.";
174  }
175 
176  bool hasChanges() const override
177  {
178  return parent_.changes_ > 0;
179  }
180 
181  bool write() override
182  {
183  std::filesystem::path path = getPath();
184  createParentFolders(path);
185  return parent_.write(path);
186  }
187 
188  protected:
190  };
191 
193  {
194  public:
195  GeneratedJointLimits(const std::filesystem::path& package_path, const GeneratedTime& last_gen_time,
196  SRDFConfig& parent)
197  : YamlGeneratedFile(package_path, last_gen_time), parent_(parent)
198  {
199  }
200 
201  std::filesystem::path getRelativePath() const override
202  {
203  return JOINT_LIMITS_FILE;
204  }
205 
206  std::string getDescription() const override
207  {
208  return "Contains additional information about joints that appear in your planning groups that is not "
209  "contained in the URDF, as well as allowing you to set maximum and minimum limits for velocity "
210  "and acceleration than those contained in your URDF. This information is used by our trajectory "
211  "filtering system to assign reasonable velocities and timing for the trajectory before it is "
212  "passed to the robot's controllers.";
213  }
214 
215  bool hasChanges() const override
216  {
217  return false; // Can't be changed just yet
218  }
219 
220  bool writeYaml(YAML::Emitter& emitter) override;
221 
222  protected:
224  };
225 
227  {
228  public:
229  using TemplatedGeneratedFile::TemplatedGeneratedFile;
230 
231  std::filesystem::path getRelativePath() const override
232  {
233  return CARTESIAN_LIMITS_FILE;
234  }
235 
236  std::filesystem::path getTemplatePath() const override
237  {
238  return getSharePath("moveit_setup_framework") / "templates" / CARTESIAN_LIMITS_FILE;
239  }
240 
241  std::string getDescription() const override
242  {
243  return "Cartesian velocity for planning in the workspace."
244  "The velocity is used by pilz industrial motion planner as maximum velocity for cartesian "
245  "planning requests scaled by the velocity scaling factor of an individual planning request.";
246  }
247 
248  bool hasChanges() const override
249  {
250  return false;
251  }
252  };
253 
254  void collectFiles(const std::filesystem::path& package_path, const GeneratedTime& last_gen_time,
255  std::vector<GeneratedFilePtr>& files) override
256  {
257  files.push_back(std::make_shared<GeneratedSRDF>(package_path, last_gen_time, *this));
258  files.push_back(std::make_shared<GeneratedJointLimits>(package_path, last_gen_time, *this));
259  files.push_back(std::make_shared<GeneratedCartesianLimits>(package_path, last_gen_time));
260  }
261 
262  void collectVariables(std::vector<TemplateVariable>& variables) override;
263 
264  bool write(const std::filesystem::path& path)
265  {
266  return srdf_.writeSRDF(path);
267  }
268 
269  std::filesystem::path getPath() const
270  {
271  return srdf_path_;
272  }
273 
274  unsigned long getChangeMask() const
275  {
276  return changes_;
277  }
278 
279 protected:
280  void getRelativePath();
281  void loadURDFModel();
282 
283  // ******************************************************************************************
284  // SRDF Data
285  // ******************************************************************************************
287  std::filesystem::path srdf_path_;
288 
290  std::filesystem::path srdf_pkg_relative_path_;
291 
293  srdf::SRDFWriter srdf_;
294 
295  std::shared_ptr<urdf::Model> urdf_model_;
296 
297  moveit::core::RobotModelPtr robot_model_;
298 
300  planning_scene::PlanningScenePtr planning_scene_;
301 
302  // bitfield of changes (composed of InformationFields)
303  unsigned long changes_;
304 };
305 } // 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