create_ikfast_moveit_plugin.py
Go to the documentation of this file.
1 #!/usr/bin/env python3
2 
3 """
4 IKFast Plugin Generator for MoveIt
5 
6 Creates a kinematics plugin using the output of IKFast from OpenRAVE.
7 This plugin and the move_group node can be used as a general
8 kinematics service, from within the moveit planning environment, or in
9 your own ROS node.
10 
11 Author: Dave Coleman, PickNik Robotics
12  Michael Lautman, PickNik Robotics
13  Based heavily on the arm_kinematic_tools package by Jeremy Zoss, SwRI
14  and the arm_navigation plugin generator by David Butterworth, KAIST
15 
16 Date: March 2013
17 
18 """
19 """
20 Copyright (c) 2013, Jeremy Zoss, SwRI
21 All rights reserved.
22 
23 Redistribution and use in source and binary forms, with or without
24 modification, are permitted provided that the following conditions are met:
25 
26 * Redistributions of source code must retain the above copyright
27 notice, this list of conditions and the following disclaimer.
28 * Redistributions in binary form must reproduce the above copyright
29 notice, this list of conditions and the following disclaimer in the
30 documentation and/or other materials provided with the distribution.
31 * Neither the name of the Willow Garage, Inc. nor the names of its
32 contributors may be used to endorse or promote products derived from
33 this software without specific prior written permission.
34 
35 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
36 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
37 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
38 ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
39 IABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
40 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
41 SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
42 INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
43 CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
44 ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
45 POSSIBILITY OF SUCH DAMAGE.
46 """
47 
48 import re
49 import os
50 import yaml
51 from lxml import etree
52 from getpass import getuser
53 import shutil
54 import argparse
55 
56 try:
57  from roslib.packages import get_pkg_dir, InvalidROSPkgException
58 except ImportError:
59  print("Failed to import roslib. No ROS environment available? Trying without.")
60  # define stubs
61  class InvalidROSPkgException(Exception):
62  pass
63 
64  def get_pkg_dir(pkg_name):
65  raise InvalidROSPkgException(f"Failed to locate ROS package {pkg_name}")
66 
67 
68 # Package containing this file
69 plugin_gen_pkg = "moveit_kinematics"
70 # Allowed search modes, see SEARCH_MODE enum in template file
71 search_modes = ["OPTIMIZE_MAX_JOINT", "OPTIMIZE_FREE_JOINT"]
72 
73 
75  parser = argparse.ArgumentParser(
76  description="Generate an IKFast MoveIt kinematic plugin"
77  )
78  parser.add_argument("robot_name", help="The name of your robot")
79  parser.add_argument(
80  "planning_group_name",
81  help="The name of the planning group for which your IKFast solution was generated",
82  )
83  parser.add_argument(
84  "ikfast_plugin_pkg",
85  help="The name of the MoveIt IKFast Kinematics Plugin to be created/updated",
86  )
87  parser.add_argument(
88  "base_link_name",
89  help="The name of the base link that was used when generating your IKFast solution",
90  )
91  parser.add_argument(
92  "eef_link_name",
93  help="The name of the end effector link that was used when generating your IKFast solution",
94  )
95  parser.add_argument(
96  "ikfast_output_path",
97  help="The full path to the analytic IK solution output by IKFast",
98  )
99  parser.add_argument(
100  "--search_mode",
101  default=search_modes[0],
102  help="The search mode used to solve IK for robots with more than 6DOF",
103  )
104  parser.add_argument(
105  "--srdf_filename", help="The name of your robot. Defaults to <robot_name>.srdf"
106  )
107  parser.add_argument(
108  "--robot_name_in_srdf",
109  help="The name of your robot as defined in the srdf. Defaults to <robot_name>",
110  )
111  parser.add_argument(
112  "--moveit_config_pkg",
113  help="The robot moveit_config package. Defaults to <robot_name>_moveit_config",
114  )
115  parser.add_argument(
116  "--eef_direction",
117  type=float,
118  nargs=3,
119  metavar=("X", "Y", "Z"),
120  default=[0, 0, 1],
121  help="The end effector's direction vector defined in its own frame, which is used to generate necessary parameters to a IKFast solver of one of the following types: Direction3D, Ray4D, TranslationDirection5D, Translation*AxisAngle4D, and Translation*AxisAngle*Norm4D. When not specified, a unit-z vector, i.e. 0 0 1, is adopted as default",
122  )
123  return parser
124 
125 
127  if args.srdf_filename is None:
128  args.srdf_filename = args.robot_name + ".srdf"
129  if args.robot_name_in_srdf is None:
130  args.robot_name_in_srdf = args.robot_name
131  if args.moveit_config_pkg is None:
132  args.moveit_config_pkg = args.robot_name + "_moveit_config"
133 
134 
135 def print_args(args):
136  print("Creating IKFastKinematicsPlugin with parameters: ")
137  print(f" robot_name: {args.robot_name}")
138  print(f" base_link_name: {args.base_link_name}")
139  print(f" eef_link_name: {args.eef_link_name}")
140  print(f" planning_group_name: {args.planning_group_name}")
141  print(f" ikfast_plugin_pkg: {args.ikfast_plugin_pkg}")
142  print(f" ikfast_output_path: {args.ikfast_output_path}")
143  print(f" search_mode: {args.search_mode}")
144  print(f" srdf_filename: {args.srdf_filename}")
145  print(f" robot_name_in_srdf: {args.robot_name_in_srdf}")
146  print(f" moveit_config_pkg: {args.moveit_config_pkg}")
147  print(
148  f" eef_direction: {args.eef_direction[0]:g} {args.eef_direction[1]:g} {args.eef_direction[2]:g}"
149  )
150  print("")
151 
152 
153 def update_deps(reqd_deps, req_type, e_parent):
154  curr_deps = [e.text for e in e_parent.findall(req_type)]
155  missing_deps = set(reqd_deps) - set(curr_deps)
156  for dep in missing_deps:
157  etree.SubElement(e_parent, req_type).text = dep
158 
159 
161  if not os.path.exists(args.ikfast_output_path):
162  raise Exception("Can't find IKFast source code at " + args.ikfast_output_path)
163 
164  # Detect version of IKFast used to generate solver code
165  solver_version = 0
166  with open(args.ikfast_output_path, "r") as src:
167  for line in src:
168  if line.startswith("/// ikfast version"):
169  line_search = re.search("ikfast version (.*) generated", line)
170  if line_search:
171  solver_version = int(line_search.group(1), 0) & ~0x10000000
172  break
173  print(f"Found source code generated by IKFast version {solver_version}")
174 
175  # Chose template depending on IKFast version
176  if solver_version >= 56:
177  setattr(args, "template_version", 61)
178  else:
179  raise Exception("This converter requires IKFast 0.5.6 or newer.")
180 
181 
182 def xmlElement(name, text=None, **attributes):
183  e = etree.Element(name, **attributes)
184  e.text = text
185  return e
186 
187 
189  try:
190  setattr(args, "ikfast_plugin_pkg_path", get_pkg_dir(args.ikfast_plugin_pkg))
191  except InvalidROSPkgException:
192  args.ikfast_plugin_pkg_path = os.path.abspath(args.ikfast_plugin_pkg)
193  print(
194  f"Createing new package {args.ikfast_plugin_pkg} it in {args.ikfast_plugin_pkg_path}."
195  )
196  # update pkg name to basename of path
197  args.ikfast_plugin_pkg = os.path.basename(args.ikfast_plugin_pkg_path)
198 
199  src_path = args.ikfast_plugin_pkg_path + "/src/"
200  if not os.path.exists(src_path):
201  os.makedirs(src_path)
202 
203  include_path = args.ikfast_plugin_pkg_path + "/include/"
204  if not os.path.exists(include_path):
205  os.makedirs(include_path)
206 
207  # Create package.xml
208  pkg_xml_path = args.ikfast_plugin_pkg_path + "/package.xml"
209  if not os.path.exists(pkg_xml_path):
210  root = xmlElement("package", format="2")
211  root.append(xmlElement("name", text=args.ikfast_plugin_pkg))
212  root.append(xmlElement("version", text="0.0.0"))
213  root.append(
214  xmlElement("description", text="IKFast plugin for " + args.robot_name)
215  )
216  root.append(xmlElement("license", text="BSD"))
217  user_name = getuser()
218  root.append(
219  xmlElement("maintainer", email=f"{user_name}@todo.todo", text=user_name)
220  )
221  root.append(xmlElement("buildtool_depend", text="catkin"))
222  etree.ElementTree(root).write(
223  pkg_xml_path, xml_declaration=True, pretty_print=True, encoding="UTF-8"
224  )
225  print(f"Created package.xml at: '{pkg_xml_path}'")
226 
227 
229  for candidate in [os.path.dirname(__file__) + "/../templates"]:
230  if os.path.exists(candidate) and os.path.exists(candidate + "/ikfast.h"):
231  return os.path.realpath(candidate)
232  try:
233  return os.path.join(
234  get_pkg_dir(plugin_gen_pkg), "ikfast_kinematics_plugin/templates"
235  )
236  except InvalidROSPkgException:
237  raise Exception(f"Can't find package {plugin_gen_pkg}")
238 
239 
241  # Copy the source code generated by IKFast into our src folder
242  src_path = args.ikfast_plugin_pkg_path + "/src/"
243  solver_file_path = (
244  src_path
245  + args.robot_name
246  + "_"
247  + args.planning_group_name
248  + "_ikfast_solver.cpp"
249  )
250  if not os.path.exists(solver_file_path) or not os.path.samefile(
251  args.ikfast_output_path, solver_file_path
252  ):
253  shutil.copy2(args.ikfast_output_path, solver_file_path)
254 
255  if not os.path.exists(solver_file_path):
256  raise Exception(
257  f"Failed to copy IKFast source code from '{args.ikfast_output_path}' to '{solver_file_path}'\n"
258  "Manually copy the source file generated by IKFast to this location and re-run"
259  )
260  # Remember ikfast solver file for update of MoveIt package
261  args.ikfast_output_path = solver_file_path
262 
263  # Get template folder location
264  template_dir = find_template_dir()
265 
266  # namespace for the plugin
267  setattr(args, "namespace", args.robot_name + "_" + args.planning_group_name)
268  replacements = dict(
269  _ROBOT_NAME_=args.robot_name,
270  _GROUP_NAME_=args.planning_group_name,
271  _SEARCH_MODE_=args.search_mode,
272  _EEF_LINK_=args.eef_link_name,
273  _BASE_LINK_=args.base_link_name,
274  _PACKAGE_NAME_=args.ikfast_plugin_pkg,
275  _NAMESPACE_=args.namespace,
276  _EEF_DIRECTION_=f"{args.eef_direction[0]:g}, {args.eef_direction[1]:g}, {args.eef_direction[2]:g}",
277  )
278 
279  # Copy ikfast header file
280  copy_file(
281  template_dir + "/ikfast.h",
282  args.ikfast_plugin_pkg_path + "/include/ikfast.h",
283  "ikfast header file",
284  )
285  # Create ikfast plugin template
286  copy_file(
287  template_dir
288  + "/ikfast"
289  + str(args.template_version)
290  + "_moveit_plugin_template.cpp",
291  args.ikfast_plugin_pkg_path
292  + "/src/"
293  + args.robot_name
294  + "_"
295  + args.planning_group_name
296  + "_ikfast_moveit_plugin.cpp",
297  "ikfast plugin file",
298  replacements,
299  )
300 
301  # Create plugin definition .xml file
302  ik_library_name = args.namespace + "_moveit_ikfast_plugin"
303  plugin_def = etree.Element("library", path="lib/lib" + ik_library_name)
304  setattr(args, "plugin_name", args.namespace + "/IKFastKinematicsPlugin")
305  cl = etree.SubElement(
306  plugin_def,
307  "class",
308  name=args.plugin_name,
309  type=args.namespace + "::IKFastKinematicsPlugin",
310  base_class_type="kinematics::KinematicsBase",
311  )
312  desc = etree.SubElement(cl, "description")
313  desc.text = f"IKFast{args.template_version} plugin for closed-form kinematics of {args.robot_name} {args.planning_group_name}"
314 
315  # Write plugin definition to file
316  plugin_file_name = ik_library_name + "_description.xml"
317  plugin_file_path = args.ikfast_plugin_pkg_path + "/" + plugin_file_name
318  etree.ElementTree(plugin_def).write(
319  plugin_file_path, xml_declaration=True, pretty_print=True, encoding="UTF-8"
320  )
321  print(f"Created plugin definition at '{plugin_file_path}'")
322 
323  # Create CMakeLists file
324  replacements.update(dict(_LIBRARY_NAME_=ik_library_name))
325  copy_file(
326  template_dir + "/CMakeLists.txt",
327  args.ikfast_plugin_pkg_path + "/CMakeLists.txt",
328  "cmake file",
329  replacements,
330  )
331 
332  # Add plugin export to package manifest
333  parser = etree.XMLParser(remove_blank_text=True)
334  package_file_name = args.ikfast_plugin_pkg_path + "/package.xml"
335  package_xml = etree.parse(package_file_name, parser).getroot()
336 
337  # Make sure at least all required dependencies are in the depends lists
338  build_deps = [
339  "liblapack-dev",
340  "moveit_core",
341  "pluginlib",
342  "roscpp",
343  "tf2_kdl",
344  "tf2_eigen",
345  ]
346  run_deps = ["liblapack-dev", "moveit_core", "pluginlib", "roscpp"]
347 
348  update_deps(build_deps, "build_depend", package_xml)
349  update_deps(run_deps, "exec_depend", package_xml)
350 
351  # Check that plugin definition file is in the export list
352  new_export = etree.Element("moveit_core", plugin="${prefix}/" + plugin_file_name)
353 
354  export_element = package_xml.find("export")
355  if export_element is None:
356  export_element = etree.SubElement(package_xml, "export")
357 
358  found = False
359  for el in export_element.findall("moveit_core"):
360  found = etree.tostring(new_export) == etree.tostring(el)
361  if found:
362  break
363 
364  if not found:
365  export_element.append(new_export)
366 
367  # Always write the package xml file, even if there are no changes, to ensure
368  # proper encodings are used in the future (UTF-8)
369  etree.ElementTree(package_xml).write(
370  package_file_name, xml_declaration=True, pretty_print=True, encoding="UTF-8"
371  )
372  print(f"Wrote package.xml at '{package_file_name}'")
373 
374  # Create a script for easily updating the plugin in the future in case the plugin needs to be updated
375  easy_script_file_path = args.ikfast_plugin_pkg_path + "/update_ikfast_plugin.sh"
376  with open(easy_script_file_path, "w") as f:
377  f.write(
378  "search_mode="
379  + args.search_mode
380  + "\n"
381  + "srdf_filename="
382  + args.srdf_filename
383  + "\n"
384  + "robot_name_in_srdf="
385  + args.robot_name_in_srdf
386  + "\n"
387  + "moveit_config_pkg="
388  + args.moveit_config_pkg
389  + "\n"
390  + "robot_name="
391  + args.robot_name
392  + "\n"
393  + "planning_group_name="
394  + args.planning_group_name
395  + "\n"
396  + "ikfast_plugin_pkg="
397  + args.ikfast_plugin_pkg
398  + "\n"
399  + "base_link_name="
400  + args.base_link_name
401  + "\n"
402  + "eef_link_name="
403  + args.eef_link_name
404  + "\n"
405  + "ikfast_output_path="
406  + args.ikfast_output_path
407  + "\n"
408  + "eef_direction="
409  + f'"{args.eef_direction[0]:g} {args.eef_direction[1]:g} {args.eef_direction[2]:g}"'
410  + "\n\n"
411  + "rosrun moveit_kinematics create_ikfast_moveit_plugin.py\\\n"
412  + " --search_mode=$search_mode\\\n"
413  + " --srdf_filename=$srdf_filename\\\n"
414  + " --robot_name_in_srdf=$robot_name_in_srdf\\\n"
415  + " --moveit_config_pkg=$moveit_config_pkg\\\n"
416  + " --eef_direction $eef_direction\\\n"
417  + " $robot_name\\\n"
418  + " $planning_group_name\\\n"
419  + " $ikfast_plugin_pkg\\\n"
420  + " $base_link_name\\\n"
421  + " $eef_link_name\\\n"
422  + " $ikfast_output_path\n"
423  )
424 
425  print(f"Created update plugin script at '{easy_script_file_path}'")
426 
427 
429  try:
430  moveit_config_pkg_path = get_pkg_dir(args.moveit_config_pkg)
431  except InvalidROSPkgException:
432  raise RuntimeError(f"Failed to find package: {args.moveit_config_pkg}")
433 
434  # SRDF sanity checks
435  try:
436  srdf_file_name = moveit_config_pkg_path + "/config/" + args.srdf_filename
437  srdf = etree.parse(srdf_file_name).getroot()
438 
439  robot_name = srdf.get("name")
440  if args.robot_name_in_srdf != robot_name:
441  raise RuntimeWarning(
442  f"Robot name in srdf ('{robot_name}') doesn't match expected name ('{args.robot_name_in_srdf}')"
443  )
444 
445  groups = [g.get("name") for g in srdf.findall("group")]
446  if args.planning_group_name not in groups:
447  raise RuntimeWarning(
448  f"Planning group '{args.planning_group_name}' not defined in the SRDF."
449  " Available groups: \n" + ", ".join(groups)
450  )
451 
452  except IOError:
453  print(f"Failed to find SRDF file: {srdf_file_name}")
454  except etree.XMLSyntaxError as err:
455  print(f"Failed to parse xml in file: {srdf_file_name}\n{err.msg}")
456 
457  # Modify kinematics.yaml file
458  kin_yaml_file_name = moveit_config_pkg_path + "/config/kinematics.yaml"
459  with open(kin_yaml_file_name, "r") as f:
460  kin_yaml_data = yaml.safe_load(f)
461 
462  try:
463  kin_yaml_data[args.planning_group_name]["kinematics_solver"] = args.plugin_name
464  except KeyError:
465  # create new group entry
466  print(
467  f"Creating new planning group entry in kinematics.yaml for '{args.planning_group_name}'"
468  )
469  kin_yaml_data[args.planning_group_name] = dict(
470  kinematics_solver=args.plugin_name
471  )
472 
473  with open(kin_yaml_file_name, "w") as f:
474  yaml.dump(kin_yaml_data, f, default_flow_style=False)
475 
476  print(f"Modified kinematics.yaml at '{kin_yaml_file_name}'")
477 
478 
479 def copy_file(src_path, dest_path, description, replacements=None):
480  if not os.path.exists(src_path):
481  raise Exception(f"Can't find {description} at '{src_path}'")
482 
483  if replacements is None:
484  replacements = dict()
485 
486  with open(src_path, "r") as f:
487  content = f.read()
488 
489  # replace templates
490  for key, value in replacements.items():
491  content = re.sub(key, value, content)
492 
493  with open(dest_path, "w") as f:
494  f.write(content)
495  print(f"Created {description} at '{dest_path}'")
496 
497 
498 def main():
499  parser = create_parser()
500  args = parser.parse_args()
501 
502  populate_optional(args)
503  print_args(args)
507  try:
509  except Exception as ex:
510  print(
511  f"""Failed to update MoveIt package:
512 {ex}
513 Update your kinematics.yaml manually to include the following configuration:
514 {args.planning_group_name}:
515  kinematics_solver: {args.plugin_name}"""
516  )
517 
518 
519 if __name__ == "__main__":
520  main()
create_ikfast_moveit_plugin.update_moveit_package
def update_moveit_package(args)
Definition: create_ikfast_moveit_plugin.py:428
create_ikfast_moveit_plugin.get_pkg_dir
def get_pkg_dir(pkg_name)
Definition: create_ikfast_moveit_plugin.py:64
create_ikfast_moveit_plugin.create_parser
def create_parser()
Definition: create_ikfast_moveit_plugin.py:74
create_ikfast_moveit_plugin.find_template_dir
def find_template_dir()
Definition: create_ikfast_moveit_plugin.py:228
create_ikfast_moveit_plugin.update_deps
def update_deps(reqd_deps, req_type, e_parent)
Definition: create_ikfast_moveit_plugin.py:153
create_ikfast_moveit_plugin.print_args
def print_args(args)
Definition: create_ikfast_moveit_plugin.py:135
create_ikfast_moveit_plugin.populate_optional
def populate_optional(args)
Definition: create_ikfast_moveit_plugin.py:126
create_ikfast_moveit_plugin.update_ikfast_package
def update_ikfast_package(args)
Definition: create_ikfast_moveit_plugin.py:240
create_ikfast_moveit_plugin.xmlElement
def xmlElement(name, text=None, **attributes)
Definition: create_ikfast_moveit_plugin.py:182
create_ikfast_moveit_plugin.validate_openrave_version
def validate_openrave_version(args)
Definition: create_ikfast_moveit_plugin.py:160
create_ikfast_moveit_plugin.InvalidROSPkgException
Definition: create_ikfast_moveit_plugin.py:61
create_ikfast_moveit_plugin.copy_file
def copy_file(src_path, dest_path, description, replacements=None)
Definition: create_ikfast_moveit_plugin.py:479
create_ikfast_moveit_plugin.create_ikfast_package
def create_ikfast_package(args)
Definition: create_ikfast_moveit_plugin.py:188
create_ikfast_moveit_plugin.main
def main()
Definition: create_ikfast_moveit_plugin.py:498


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Tue Jun 18 2024 02:24:28