|
| 1 | +#!/usr/bin/env python3 |
| 2 | +# -*- coding: utf-8 -*- |
| 3 | +# |
| 4 | +# Copyright 2022 Stéphane Caron |
| 5 | +# |
| 6 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 7 | +# you may not use this file except in compliance with the License. |
| 8 | +# You may obtain a copy of the License at |
| 9 | +# |
| 10 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 11 | +# |
| 12 | +# Unless required by applicable law or agreed to in writing, software |
| 13 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 14 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 15 | +# See the License for the specific language governing permissions and |
| 16 | +# limitations under the License. |
| 17 | + |
| 18 | +""" |
| 19 | +List or show robot descriptions from the command line. |
| 20 | +
|
| 21 | +Note: |
| 22 | + This tool requires `yourdfpy` which is an optional dependency. It can be |
| 23 | + installed separately (``pip install yourdfpy``), or when robot descriptions |
| 24 | + are installed via ``pip install robot_descriptions[cli]``. |
| 25 | +""" |
| 26 | + |
| 27 | +import argparse |
| 28 | +import sys |
| 29 | +from functools import partial |
| 30 | +from importlib import import_module # type: ignore |
| 31 | +from typing import List |
| 32 | + |
| 33 | +import yourdfpy # pylint: disable=import-error |
| 34 | +from yourdfpy.viz import ( # pylint: disable=import-error |
| 35 | + generate_joint_limit_trajectory, |
| 36 | + viewer_callback, |
| 37 | +) |
| 38 | + |
| 39 | +from robot_descriptions._description_names import DESCRIPTION_NAMES |
| 40 | + |
| 41 | + |
| 42 | +def positive_float(value) -> float: |
| 43 | + """ |
| 44 | + Convert a value to float and check that it is positive. |
| 45 | +
|
| 46 | + Args: |
| 47 | + value: Value to convert. |
| 48 | +
|
| 49 | + Returns: |
| 50 | + Converted value. |
| 51 | +
|
| 52 | + Raises: |
| 53 | + ArgumentTypeError: if the value is not positive. |
| 54 | + """ |
| 55 | + float_value = float(value) |
| 56 | + if float_value <= 0.0: |
| 57 | + raise argparse.ArgumentTypeError( |
| 58 | + f"Duration {value} is not a positive number" |
| 59 | + ) |
| 60 | + return float_value |
| 61 | + |
| 62 | + |
| 63 | +def get_argument_parser() -> argparse.ArgumentParser: |
| 64 | + """ |
| 65 | + Parse command-line arguments. |
| 66 | +
|
| 67 | + Returns: |
| 68 | + Argument parser. |
| 69 | + """ |
| 70 | + parser = argparse.ArgumentParser(description=__doc__) |
| 71 | + subparsers = parser.add_subparsers(title="subcommands", dest="subcmd") |
| 72 | + |
| 73 | + # list -------------------------------------------------------------------- |
| 74 | + subparsers.add_parser( |
| 75 | + "list", |
| 76 | + help="list all available robot descriptions", |
| 77 | + ) |
| 78 | + |
| 79 | + # show -------------------------------------------------------------------- |
| 80 | + parser_show = subparsers.add_parser( |
| 81 | + "show", |
| 82 | + help="load and display a given robot description", |
| 83 | + ) |
| 84 | + parser_show.add_argument( |
| 85 | + "name", |
| 86 | + help="name of the robot description", |
| 87 | + ) |
| 88 | + parser_show.add_argument( |
| 89 | + "-c", |
| 90 | + "--configuration", |
| 91 | + nargs="+", |
| 92 | + type=float, |
| 93 | + help="configuration of the visualized robot description", |
| 94 | + ) |
| 95 | + parser_show.add_argument( |
| 96 | + "--collision", |
| 97 | + action="store_true", |
| 98 | + help="use collision geometry for the visualized robot description", |
| 99 | + ) |
| 100 | + |
| 101 | + # animate ----------------------------------------------------------------- |
| 102 | + parser_animate = subparsers.add_parser( |
| 103 | + "animate", |
| 104 | + help=( |
| 105 | + "animate a robot description by interpolating " |
| 106 | + "each joint between its limits", |
| 107 | + ), |
| 108 | + ) |
| 109 | + parser_animate.add_argument( |
| 110 | + "name", |
| 111 | + help="name of the robot description", |
| 112 | + ) |
| 113 | + parser_animate.add_argument( |
| 114 | + "--collision", |
| 115 | + action="store_true", |
| 116 | + help="use collision geometry for the visualized robot description", |
| 117 | + ) |
| 118 | + parser_animate.add_argument( |
| 119 | + "--loop-time", |
| 120 | + type=positive_float, |
| 121 | + default=6.0, |
| 122 | + help="duration of animation loop in seconds", |
| 123 | + ) |
| 124 | + |
| 125 | + return parser |
| 126 | + |
| 127 | + |
| 128 | +def show( |
| 129 | + name: str, |
| 130 | + configuration: List[float], |
| 131 | + collision: bool, |
| 132 | +) -> None: |
| 133 | + """ |
| 134 | + Load and display a given robot description. |
| 135 | +
|
| 136 | + Args: |
| 137 | + name: Name of the robot description. |
| 138 | + configuration: Optional robot configuration. |
| 139 | + collision: Use collision rather than visualization geometry. |
| 140 | + """ |
| 141 | + try: |
| 142 | + module = import_module(f"robot_descriptions.{name}") |
| 143 | + except ModuleNotFoundError: |
| 144 | + module = import_module(f"robot_descriptions.{name}_description") |
| 145 | + |
| 146 | + if collision: |
| 147 | + robot = yourdfpy.URDF.load( |
| 148 | + module.URDF_PATH, |
| 149 | + build_collision_scene_graph=True, |
| 150 | + load_collision_meshes=True, |
| 151 | + ) |
| 152 | + else: |
| 153 | + robot = yourdfpy.URDF.load(module.URDF_PATH) |
| 154 | + |
| 155 | + if configuration: |
| 156 | + robot.update_cfg(configuration) |
| 157 | + robot.show( |
| 158 | + collision_geometry=collision, |
| 159 | + ) |
| 160 | + |
| 161 | + |
| 162 | +def animate( |
| 163 | + name: str, |
| 164 | + collision: bool, |
| 165 | + loop_time: float, |
| 166 | +) -> None: |
| 167 | + """ |
| 168 | + Load and animate a given robot description. |
| 169 | +
|
| 170 | + Args: |
| 171 | + name: Name of the robot description. |
| 172 | + collision: Use collision rather than visualization geometry. |
| 173 | + loop_time: Animation duration in seconds. |
| 174 | + """ |
| 175 | + try: |
| 176 | + module = import_module(f"robot_descriptions.{name}") |
| 177 | + except ModuleNotFoundError: |
| 178 | + module = import_module(f"robot_descriptions.{name}_description") |
| 179 | + |
| 180 | + if collision: |
| 181 | + robot = yourdfpy.URDF.load( |
| 182 | + module.URDF_PATH, |
| 183 | + build_collision_scene_graph=True, |
| 184 | + load_collision_meshes=True, |
| 185 | + ) |
| 186 | + else: |
| 187 | + robot = yourdfpy.URDF.load(module.URDF_PATH) |
| 188 | + |
| 189 | + robot.show( |
| 190 | + collision_geometry=collision, |
| 191 | + callback=partial( |
| 192 | + viewer_callback, |
| 193 | + urdf_model=robot, |
| 194 | + loop_time=loop_time, |
| 195 | + trajectory=generate_joint_limit_trajectory( |
| 196 | + urdf_model=robot, loop_time=loop_time |
| 197 | + ), |
| 198 | + ), |
| 199 | + ) |
| 200 | + |
| 201 | + |
| 202 | +def main(argv=None): |
| 203 | + """ |
| 204 | + Command line entry point. |
| 205 | + """ |
| 206 | + parser = get_argument_parser() |
| 207 | + args = parser.parse_args(argv) |
| 208 | + if args.subcmd is None: |
| 209 | + parser.print_help() |
| 210 | + sys.exit(-1) |
| 211 | + |
| 212 | + if args.subcmd == "list": |
| 213 | + print("\n".join(DESCRIPTION_NAMES)) |
| 214 | + elif args.subcmd == "show": |
| 215 | + show(args.name, args.configuration, args.collision) |
| 216 | + elif args.subcmd == "animate": |
| 217 | + animate(args.name, args.collision, args.loop_time) |
0 commit comments