4 IKFast Plugin Generator for MoveIt
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
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
20 Copyright (c) 2013, Jeremy Zoss, SwRI
23 Redistribution and use in source and binary forms, with or without
24 modification, are permitted provided that the following conditions are met:
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.
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.
51 from lxml
import etree
52 from getpass
import getuser
57 from roslib.packages
import get_pkg_dir, InvalidROSPkgException
59 print(
"Failed to import roslib. No ROS environment available? Trying without.")
65 raise InvalidROSPkgException(f
"Failed to locate ROS package {pkg_name}")
69 plugin_gen_pkg =
"moveit_kinematics"
71 search_modes = [
"OPTIMIZE_MAX_JOINT",
"OPTIMIZE_FREE_JOINT"]
75 parser = argparse.ArgumentParser(
76 description=
"Generate an IKFast MoveIt kinematic plugin"
78 parser.add_argument(
"robot_name", help=
"The name of your robot")
80 "planning_group_name",
81 help=
"The name of the planning group for which your IKFast solution was generated",
85 help=
"The name of the MoveIt IKFast Kinematics Plugin to be created/updated",
89 help=
"The name of the base link that was used when generating your IKFast solution",
93 help=
"The name of the end effector link that was used when generating your IKFast solution",
97 help=
"The full path to the analytic IK solution output by IKFast",
101 default=search_modes[0],
102 help=
"The search mode used to solve IK for robots with more than 6DOF",
105 "--srdf_filename", help=
"The name of your robot. Defaults to <robot_name>.srdf"
108 "--robot_name_in_srdf",
109 help=
"The name of your robot as defined in the srdf. Defaults to <robot_name>",
112 "--moveit_config_pkg",
113 help=
"The robot moveit_config package. Defaults to <robot_name>_moveit_config",
119 metavar=(
"X",
"Y",
"Z"),
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",
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"
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}")
148 f
" eef_direction: {args.eef_direction[0]:g} {args.eef_direction[1]:g} {args.eef_direction[2]:g}"
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
161 if not os.path.exists(args.ikfast_output_path):
162 raise Exception(
"Can't find IKFast source code at " + args.ikfast_output_path)
166 with open(args.ikfast_output_path,
"r")
as src:
168 if line.startswith(
"/// ikfast version"):
169 line_search = re.search(
"ikfast version (.*) generated", line)
171 solver_version = int(line_search.group(1), 0) & ~0x10000000
173 print(f
"Found source code generated by IKFast version {solver_version}")
176 if solver_version >= 56:
177 setattr(args,
"template_version", 61)
179 raise Exception(
"This converter requires IKFast 0.5.6 or newer.")
183 e = etree.Element(name, **attributes)
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)
194 f
"Createing new package {args.ikfast_plugin_pkg} it in {args.ikfast_plugin_pkg_path}."
197 args.ikfast_plugin_pkg = os.path.basename(args.ikfast_plugin_pkg_path)
199 src_path = args.ikfast_plugin_pkg_path +
"/src/"
200 if not os.path.exists(src_path):
201 os.makedirs(src_path)
203 include_path = args.ikfast_plugin_pkg_path +
"/include/"
204 if not os.path.exists(include_path):
205 os.makedirs(include_path)
208 pkg_xml_path = args.ikfast_plugin_pkg_path +
"/package.xml"
209 if not os.path.exists(pkg_xml_path):
211 root.append(
xmlElement(
"name", text=args.ikfast_plugin_pkg))
212 root.append(
xmlElement(
"version", text=
"0.0.0"))
214 xmlElement(
"description", text=
"IKFast plugin for " + args.robot_name)
216 root.append(
xmlElement(
"license", text=
"BSD"))
217 user_name = getuser()
219 xmlElement(
"maintainer", email=f
"{user_name}@todo.todo", text=user_name)
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"
225 print(f
"Created package.xml at: '{pkg_xml_path}'")
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)
234 get_pkg_dir(plugin_gen_pkg),
"ikfast_kinematics_plugin/templates"
236 except InvalidROSPkgException:
237 raise Exception(f
"Can't find package {plugin_gen_pkg}")
242 src_path = args.ikfast_plugin_pkg_path +
"/src/"
247 + args.planning_group_name
248 +
"_ikfast_solver.cpp"
250 if not os.path.exists(solver_file_path)
or not os.path.samefile(
251 args.ikfast_output_path, solver_file_path
253 shutil.copy2(args.ikfast_output_path, solver_file_path)
255 if not os.path.exists(solver_file_path):
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"
261 args.ikfast_output_path = solver_file_path
267 setattr(args,
"namespace", args.robot_name +
"_" + args.planning_group_name)
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}",
281 template_dir +
"/ikfast.h",
282 args.ikfast_plugin_pkg_path +
"/include/ikfast.h",
283 "ikfast header file",
289 + str(args.template_version)
290 +
"_moveit_plugin_template.cpp",
291 args.ikfast_plugin_pkg_path
295 + args.planning_group_name
296 +
"_ikfast_moveit_plugin.cpp",
297 "ikfast plugin 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(
308 name=args.plugin_name,
309 type=args.namespace +
"::IKFastKinematicsPlugin",
310 base_class_type=
"kinematics::KinematicsBase",
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}"
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"
321 print(f
"Created plugin definition at '{plugin_file_path}'")
324 replacements.update(dict(_LIBRARY_NAME_=ik_library_name))
326 template_dir +
"/CMakeLists.txt",
327 args.ikfast_plugin_pkg_path +
"/CMakeLists.txt",
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()
346 run_deps = [
"liblapack-dev",
"moveit_core",
"pluginlib",
"roscpp"]
348 update_deps(build_deps,
"build_depend", package_xml)
352 new_export = etree.Element(
"moveit_core", plugin=
"${prefix}/" + plugin_file_name)
354 export_element = package_xml.find(
"export")
355 if export_element
is None:
356 export_element = etree.SubElement(package_xml,
"export")
359 for el
in export_element.findall(
"moveit_core"):
360 found = etree.tostring(new_export) == etree.tostring(el)
365 export_element.append(new_export)
369 etree.ElementTree(package_xml).write(
370 package_file_name, xml_declaration=
True, pretty_print=
True, encoding=
"UTF-8"
372 print(f
"Wrote package.xml at '{package_file_name}'")
375 easy_script_file_path = args.ikfast_plugin_pkg_path +
"/update_ikfast_plugin.sh"
376 with open(easy_script_file_path,
"w")
as f:
384 +
"robot_name_in_srdf="
385 + args.robot_name_in_srdf
387 +
"moveit_config_pkg="
388 + args.moveit_config_pkg
393 +
"planning_group_name="
394 + args.planning_group_name
396 +
"ikfast_plugin_pkg="
397 + args.ikfast_plugin_pkg
400 + args.base_link_name
405 +
"ikfast_output_path="
406 + args.ikfast_output_path
409 + f
'"{args.eef_direction[0]:g} {args.eef_direction[1]:g} {args.eef_direction[2]:g}"'
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"
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"
425 print(f
"Created update plugin script at '{easy_script_file_path}'")
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}")
436 srdf_file_name = moveit_config_pkg_path +
"/config/" + args.srdf_filename
437 srdf = etree.parse(srdf_file_name).getroot()
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}')"
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)
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}")
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)
463 kin_yaml_data[args.planning_group_name][
"kinematics_solver"] = args.plugin_name
467 f
"Creating new planning group entry in kinematics.yaml for '{args.planning_group_name}'"
469 kin_yaml_data[args.planning_group_name] = dict(
470 kinematics_solver=args.plugin_name
473 with open(kin_yaml_file_name,
"w")
as f:
474 yaml.dump(kin_yaml_data, f, default_flow_style=
False)
476 print(f
"Modified kinematics.yaml at '{kin_yaml_file_name}'")
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}'")
483 if replacements
is None:
484 replacements = dict()
486 with open(src_path,
"r")
as f:
490 for key, value
in replacements.items():
491 content = re.sub(key, value, content)
493 with open(dest_path,
"w")
as f:
495 print(f
"Created {description} at '{dest_path}'")
500 args = parser.parse_args()
509 except Exception
as ex:
511 f
"""Failed to update MoveIt package:
513 Update your kinematics.yaml manually to include the following configuration:
514 {args.planning_group_name}:
515 kinematics_solver: {args.plugin_name}"""
519 if __name__ ==
"__main__":