From 752ecb8c465bc461983f0816beb8648d514d0542 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Mon, 7 Oct 2024 17:43:48 -0400 Subject: [PATCH 01/15] Implement get_latest_urdf() with error handling --- nodes/urdf_utils.py | 32 ++++++++++++++++++++++++++++++++ 1 file changed, 32 insertions(+) create mode 100644 nodes/urdf_utils.py diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py new file mode 100644 index 00000000..e2fe10bb --- /dev/null +++ b/nodes/urdf_utils.py @@ -0,0 +1,32 @@ +import pathlib +import stretch_body.hello_utils as hu + + +def get_latest_urdf(): + """ + Fetches the latest calibrated URDF from the calibration directory. + + Returns + ------- + str: Absolute filepath to the latest calibrated URDF. + """ + try: + fleet_dir = hu.get_fleet_directory() + except: + raise FileNotFoundError("Stretch data directory doesn't exist") from None + calibration_dir = pathlib.Path(fleet_dir) / "exported_urdf" + if not calibration_dir.is_dir(): + raise FileNotFoundError("URDF calibration directory doesn't exist") + urdf_path = calibration_dir / "stretch.urdf" + if not urdf_path.is_file(): + raise FileNotFoundError("URDF doesn't exist") + urdf_filename = str(urdf_path.absolute()) + return urdf_filename + + +def generate_urdf(): + pass + + +if __name__ == "__main__": + print(get_latest_urdf()) From 25416e47858de42bd5e9bd3288063f3aa1133986 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Tue, 8 Oct 2024 17:28:36 -0400 Subject: [PATCH 02/15] Implement get_joint_limits() --- nodes/urdf_utils.py | 50 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 50 insertions(+) diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py index e2fe10bb..b5dfc207 100644 --- a/nodes/urdf_utils.py +++ b/nodes/urdf_utils.py @@ -1,5 +1,7 @@ import pathlib +import numpy as np import stretch_body.hello_utils as hu +from typing import Dict, Optional, Tuple def get_latest_urdf(): @@ -24,9 +26,57 @@ def get_latest_urdf(): return urdf_filename +def get_joint_limits(use_original_limits=True): + """ + Enables more conservative joint limits to be set than in the + original URDF. + + If these limits are outside the originally permitted range, + the original range is used. Joint limits. Where these limits + have a value of None, the original limit is used. + + Parameters + ---------- + use_original_limits: bool + don't impose any additional limits + + Returns + ------- + dict[str, tuple(float or None, float or None)]: + mapping between joint and (lower limit, upper limit) + """ + ik_joint_limits: Dict[str, Tuple[Optional[float], Optional[float]]] = {} + if use_original_limits: + ik_joint_limits = { + "joint_mobile_base_translation": (None, None), + "joint_mobile_base_rotation": (None, None), + "joint_lift": (None, None), + "joint_arm_l0": (None, None), + "joint_wrist_yaw": (None, None), + "joint_wrist_pitch": (-0.8 * (np.pi / 2.0), None), # Beware of gimbal lock if joint_wrist_pitch is too close to -90 deg + "joint_wrist_roll": (None, None), + } + else: + ik_joint_limits = { + "joint_mobile_base_translation": (-0.25, 0.25), + "joint_mobile_base_rotation": (-(np.pi / 2.0), np.pi / 2.0), + "joint_lift": (0.01, 1.09), + "joint_arm_l0": (0.01, 0.48), + "joint_wrist_yaw": (-(np.pi / 4.0), np.pi), + "joint_wrist_pitch": (-0.9 * (np.pi / 2.0), np.pi / 20.0), + "joint_wrist_roll": (-(np.pi / 2.0), np.pi / 2.0), + } + + return ik_joint_limits + + def generate_urdf(): pass if __name__ == "__main__": print(get_latest_urdf()) + print('') + import pprint; pprint.pprint(get_joint_limits()) + print('') + pprint.pprint(get_joint_limits(use_original_limits=False)) From 0c897557de97871d862e2550c90fb5294fd0bf2d Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Tue, 8 Oct 2024 18:04:56 -0400 Subject: [PATCH 03/15] Implement make_joints_rigid() --- nodes/urdf_utils.py | 38 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py index b5dfc207..4faabcd7 100644 --- a/nodes/urdf_utils.py +++ b/nodes/urdf_utils.py @@ -1,6 +1,7 @@ import pathlib import numpy as np import stretch_body.hello_utils as hu +from urdf_parser_py import urdf as ud from typing import Dict, Optional, Tuple @@ -70,6 +71,32 @@ def get_joint_limits(use_original_limits=True): return ik_joint_limits +def make_joints_rigid(robot, ignore_joints=None): + """ + Change any joint that should be immobile for end effector IK + into a fixed joint. + + Parameters + ---------- + robot: urdf_parser_py.urdf.Robot + a manipulable URDF representation + ignore_joints: list(str) or None + which joints to keep as-is + + Returns + ------- + urdf_parser_py.urdf.Robot: + modified URDF where joints are "fixed" + """ + if ignore_joints is None: + ignore_joints = [] + + for j in robot.joint_map.keys(): + if j not in ignore_joints: + joint = robot.joint_map[j] + joint.type = "fixed" + + def generate_urdf(): pass @@ -80,3 +107,14 @@ def generate_urdf(): import pprint; pprint.pprint(get_joint_limits()) print('') pprint.pprint(get_joint_limits(use_original_limits=False)) + print('') + def print_joint_type(): + i = {} + for j in robot.joint_map: + i[j] = robot.joint_map[j].type + print(f'len={len(i)}') + pprint.pprint(i) + robot = ud.Robot.from_xml_file(get_latest_urdf()) + print_joint_type() + make_joints_rigid(robot) + print_joint_type() From ec89fc3d2954dd4549b23e65dd3b58281ede5aa8 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Tue, 8 Oct 2024 18:07:27 -0400 Subject: [PATCH 04/15] Implement merge_arm() --- nodes/urdf_utils.py | 54 +++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 52 insertions(+), 2 deletions(-) diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py index 4faabcd7..0c93ab1e 100644 --- a/nodes/urdf_utils.py +++ b/nodes/urdf_utils.py @@ -97,6 +97,54 @@ def make_joints_rigid(robot, ignore_joints=None): joint.type = "fixed" +def merge_arm(robot): + """ + Replace telescoping arm with a single prismatic joint, + which makes end-effector IK computation easier. + + Parameters + ---------- + robot: urdf_parser_py.urdf.Robot + a manipulable URDF representation + + Returns + ------- + urdf_parser_py.urdf.Robot: + modified URDF with single arm joint + """ + all_arm_joints = [ + "joint_arm_l4", + "joint_arm_l3", + "joint_arm_l2", + "joint_arm_l1", + "joint_arm_l0", + ] + prismatic_arm_joints = all_arm_joints[1:] + removed_arm_joints = all_arm_joints[1:-1] + near_proximal_arm_joint = robot.joint_map[all_arm_joints[1]] + distal_arm_joint = robot.joint_map[all_arm_joints[-1]] + + # Calculate aggregate joint characteristics + xyz_total = np.array([0.0, 0.0, 0.0]) + limit_upper_total = 0.0 + for j in prismatic_arm_joints: + joint = robot.joint_map[j] + xyz_total = xyz_total + joint.origin.xyz + limit_upper_total = limit_upper_total + joint.limit.upper + + # Directly connect the proximal and distal parts of the arm + distal_arm_joint.parent = near_proximal_arm_joint.parent + + # Make the distal prismatic joint act like the full arm + distal_arm_joint.origin.xyz = xyz_total + distal_arm_joint.limit.upper = limit_upper_total + + # Mark the eliminated joints as "fixed" + for j in removed_arm_joints: + joint = robot.joint_map[j] + joint.type = "fixed" + + def generate_urdf(): pass @@ -115,6 +163,8 @@ def print_joint_type(): print(f'len={len(i)}') pprint.pprint(i) robot = ud.Robot.from_xml_file(get_latest_urdf()) - print_joint_type() - make_joints_rigid(robot) + # print_joint_type() + # make_joints_rigid(robot) + # print_joint_type() + merge_arm(robot) print_joint_type() From cffa9c031d3bacf9bd8d992f6b9786e8448eaf6c Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Tue, 8 Oct 2024 18:12:35 -0400 Subject: [PATCH 05/15] Implement add_virtual_rotary_joint() --- nodes/urdf_utils.py | 41 ++++++++++++++++++++++++++++++++++++++++- 1 file changed, 40 insertions(+), 1 deletion(-) diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py index 0c93ab1e..fbcc81b1 100644 --- a/nodes/urdf_utils.py +++ b/nodes/urdf_utils.py @@ -145,6 +145,42 @@ def merge_arm(robot): joint.type = "fixed" +def add_virtual_rotary_joint(robot): + """ + Add virtual rotary joint for mobile base. + + Parameters + ---------- + robot: urdf_parser_py.urdf.Robot + a manipulable URDF representation + + Returns + ------- + urdf_parser_py.urdf.Robot: + modified URDF with mobile base rotation joint + """ + link_virtual_base_rotary = ud.Link( + name="virtual_base", visual=None, inertial=None, collision=None, origin=None + ) + origin_rotary = ud.Pose(xyz=[0, 0, 0], rpy=[0, 0, 0]) + limit_rotary = ud.JointLimit(effort=10, velocity=1, lower=-np.pi, upper=np.pi) + joint_mobile_base_rotation = ud.Joint( + name="joint_mobile_base_rotation", + parent="virtual_base", + child="base_link", + joint_type="revolute", + axis=[0, 0, 1], + origin=origin_rotary, + limit=limit_rotary, + dynamics=None, + safety_controller=None, + calibration=None, + mimic=None, + ) + robot.add_link(link_virtual_base_rotary) + robot.add_joint(joint_mobile_base_rotation) + + def generate_urdf(): pass @@ -166,5 +202,8 @@ def print_joint_type(): # print_joint_type() # make_joints_rigid(robot) # print_joint_type() - merge_arm(robot) + # merge_arm(robot) + # print_joint_type() + print_joint_type() + add_virtual_rotary_joint(robot) print_joint_type() From a6d5def8f136db09430326ae6d851d6abc409144 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Tue, 8 Oct 2024 18:20:28 -0400 Subject: [PATCH 06/15] Implement clip_joint_limits() --- nodes/urdf_utils.py | 36 ++++++++++++++++++++++++++---------- 1 file changed, 26 insertions(+), 10 deletions(-) diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py index fbcc81b1..1d70df6d 100644 --- a/nodes/urdf_utils.py +++ b/nodes/urdf_utils.py @@ -27,7 +27,7 @@ def get_latest_urdf(): return urdf_filename -def get_joint_limits(use_original_limits=True): +def clip_joint_limits(robot, use_original_limits=True): """ Enables more conservative joint limits to be set than in the original URDF. @@ -38,13 +38,15 @@ def get_joint_limits(use_original_limits=True): Parameters ---------- + robot: urdf_parser_py.urdf.Robot + a manipulable URDF representation use_original_limits: bool don't impose any additional limits Returns ------- - dict[str, tuple(float or None, float or None)]: - mapping between joint and (lower limit, upper limit) + urdf_parser_py.urdf.Robot: + modified URDF where joint limits are clipped """ ik_joint_limits: Dict[str, Tuple[Optional[float], Optional[float]]] = {} if use_original_limits: @@ -68,7 +70,20 @@ def get_joint_limits(use_original_limits=True): "joint_wrist_roll": (-(np.pi / 2.0), np.pi / 2.0), } - return ik_joint_limits + for j in ik_joint_limits: + joint = robot.joint_map.get(j, None) + if joint is not None: + original_upper = joint.limit.upper + requested_upper = ik_joint_limits[j][1] + if requested_upper is not None: + new_upper = min(requested_upper, original_upper) + robot.joint_map[j].limit.upper = new_upper + + original_lower = joint.limit.lower + requested_lower = ik_joint_limits[j][0] + if requested_lower is not None: + new_lower = max(requested_lower, original_lower) + robot.joint_map[j].limit.lower = new_lower def make_joints_rigid(robot, ignore_joints=None): @@ -186,16 +201,16 @@ def generate_urdf(): if __name__ == "__main__": + import pprint print(get_latest_urdf()) print('') - import pprint; pprint.pprint(get_joint_limits()) - print('') - pprint.pprint(get_joint_limits(use_original_limits=False)) - print('') def print_joint_type(): i = {} for j in robot.joint_map: - i[j] = robot.joint_map[j].type + try: + i[j] = robot.joint_map[j].limit.upper, robot.joint_map[j].limit.lower + except: + pass print(f'len={len(i)}') pprint.pprint(i) robot = ud.Robot.from_xml_file(get_latest_urdf()) @@ -204,6 +219,7 @@ def print_joint_type(): # print_joint_type() # merge_arm(robot) # print_joint_type() + # add_virtual_rotary_joint(robot) print_joint_type() - add_virtual_rotary_joint(robot) + clip_joint_limits(robot) print_joint_type() From 10c28331998a6bf4295e7b208096d1744b06e0ec Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Tue, 8 Oct 2024 18:40:44 -0400 Subject: [PATCH 07/15] Implement generate_ik_urdfs() --- nodes/urdf_utils.py | 87 +++++++++++++++++++++++++++++++++------------ 1 file changed, 64 insertions(+), 23 deletions(-) diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py index 1d70df6d..86617af3 100644 --- a/nodes/urdf_utils.py +++ b/nodes/urdf_utils.py @@ -196,30 +196,71 @@ def add_virtual_rotary_joint(robot): robot.add_joint(joint_mobile_base_rotation) -def generate_urdf(): - pass +def generate_ik_urdfs(rigid_wrist_urdf=True): + """ + Generates URDFs for IK packages. The latest calibrated + URDF is used as a starting point, then these modifications + are applied: + 1. Clip joint limits + 2. Make non-IK joints rigid + 3. Merge arm joints + 4. Add virtual rotary base joint + 5. (optionally) Make wrist joints rigid + Parameters + ---------- + rigid_wrist_urdf: bool + whether to also generate a IK URDF with a fixed dex wrist + + Returns + ------- + list(str): + one or two filepaths, depending on `rigid_wrist_urdf`, + to the generated URDFs + """ + def save_urdf(robot, file_name): + urdf_string = robot.to_xml_string() + with open(file_name, "w") as fid: + fid.write(urdf_string) -if __name__ == "__main__": - import pprint - print(get_latest_urdf()) - print('') - def print_joint_type(): - i = {} - for j in robot.joint_map: - try: - i[j] = robot.joint_map[j].limit.upper, robot.joint_map[j].limit.lower - except: - pass - print(f'len={len(i)}') - pprint.pprint(i) robot = ud.Robot.from_xml_file(get_latest_urdf()) - # print_joint_type() - # make_joints_rigid(robot) - # print_joint_type() - # merge_arm(robot) - # print_joint_type() - # add_virtual_rotary_joint(robot) - print_joint_type() clip_joint_limits(robot) - print_joint_type() + + ignore_joints = [ + "joint_lift", + "joint_arm_l0", + "joint_arm_l1", + "joint_arm_l2", + "joint_arm_l3", + "joint_wrist_yaw", + "joint_wrist_pitch", + "joint_wrist_roll", + ] + make_joints_rigid(robot, ignore_joints) + + merge_arm(robot) + + add_virtual_rotary_joint(robot) + + ret = ['/tmp/stretch_base_rotation_ik.urdf'] + save_urdf(robot, ret[-1]) + + if rigid_wrist_urdf: + ignore_joints = [ + "joint_mobile_base_translation", + "joint_mobile_base_rotation", + "joint_lift", + "joint_arm_l0", + ] + make_joints_rigid(robot, ignore_joints) + + ret.append('/tmp/stretch_base_rotation_ik_with_fixed_wrist.urdf') + save_urdf(robot, ret[-1]) + + return ret + + +if __name__ == "__main__": + print(generate_ik_urdfs()) + with open('/tmp/stretch_base_rotation_ik.urdf', 'r') as fid: + print(fid.read()) From 2906bb2b4bb9e830a6296d716ecae9f2688c2344 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Tue, 8 Oct 2024 19:48:24 -0400 Subject: [PATCH 08/15] Implement generate_urdf_from_robot() --- nodes/urdf_utils.py | 62 ++++++++++++++++++++++++++++++++++++--------- 1 file changed, 50 insertions(+), 12 deletions(-) diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py index 86617af3..d378efd9 100644 --- a/nodes/urdf_utils.py +++ b/nodes/urdf_utils.py @@ -196,7 +196,46 @@ def add_virtual_rotary_joint(robot): robot.add_joint(joint_mobile_base_rotation) -def generate_ik_urdfs(rigid_wrist_urdf=True): +def generate_urdf_from_robot(robot, app_name, description=None): + """ + Renders a `robot` URDF object out to a file in the /tmp + folder. The file will be unique to your application given + the `app_name` isn't the same as other applications. + + This enables you to safety generate URDFs on-the-fly + to be used by your app. E.g. `generate_ik_urdfs()` uses + this method to generate "calibrated" inverse kinematics + URDFs, so each robot's unique backlash and skew parameters + are baked into the IK calculations. + + Parameters + ---------- + robot: urdf_parser_py.urdf.Robot + the URDF representation to render out to a file + app_name: str + the name of your application + description: str or None + further description of the URDF + + Returns + ------- + str: filepath of the generated URDF + """ + if description is None: + description = "custom" + + def save_urdf(robot, file_name): + urdf_string = robot.to_xml_string() + with open(file_name, "w") as fid: + fid.write(urdf_string) + + filename = f'/tmp/{app_name}_{description}.urdf' + save_urdf(robot, filename) + + return filename + + +def generate_ik_urdfs(app_name, rigid_wrist_urdf=True): """ Generates URDFs for IK packages. The latest calibrated URDF is used as a starting point, then these modifications @@ -209,7 +248,9 @@ def generate_ik_urdfs(rigid_wrist_urdf=True): Parameters ---------- - rigid_wrist_urdf: bool + app_name: str + the name of your application + rigid_wrist_urdf: bool or None whether to also generate a IK URDF with a fixed dex wrist Returns @@ -218,10 +259,6 @@ def generate_ik_urdfs(rigid_wrist_urdf=True): one or two filepaths, depending on `rigid_wrist_urdf`, to the generated URDFs """ - def save_urdf(robot, file_name): - urdf_string = robot.to_xml_string() - with open(file_name, "w") as fid: - fid.write(urdf_string) robot = ud.Robot.from_xml_file(get_latest_urdf()) clip_joint_limits(robot) @@ -242,8 +279,9 @@ def save_urdf(robot, file_name): add_virtual_rotary_joint(robot) - ret = ['/tmp/stretch_base_rotation_ik.urdf'] - save_urdf(robot, ret[-1]) + ret = [] + fpath = generate_urdf_from_robot(robot, app_name, 'base_rotation_ik') + ret.append(fpath) if rigid_wrist_urdf: ignore_joints = [ @@ -254,13 +292,13 @@ def save_urdf(robot, file_name): ] make_joints_rigid(robot, ignore_joints) - ret.append('/tmp/stretch_base_rotation_ik_with_fixed_wrist.urdf') - save_urdf(robot, ret[-1]) + fpath = generate_urdf_from_robot(robot, app_name, 'base_rotation_ik_with_fixed_wrist') + ret.append(fpath) return ret if __name__ == "__main__": - print(generate_ik_urdfs()) - with open('/tmp/stretch_base_rotation_ik.urdf', 'r') as fid: + print(generate_ik_urdfs('stretch_web_teleop')) + with open('/tmp/stretch_web_teleop_base_rotation_ik.urdf', 'r') as fid: print(fid.read()) From d572b40ec45ad60583192c9fe56ad34d7c5be035 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Tue, 8 Oct 2024 19:56:58 -0400 Subject: [PATCH 09/15] Generate Web Teleop's URDF on-the-fly --- launch/web_interface.launch.py | 17 ----------------- nodes/move_to_pregrasp.py | 9 ++++----- nodes/urdf_utils.py | 4 +++- urdf/.placeholder | 0 4 files changed, 7 insertions(+), 23 deletions(-) delete mode 100644 urdf/.placeholder diff --git a/launch/web_interface.launch.py b/launch/web_interface.launch.py index 5931ca3a..87380c9b 100644 --- a/launch/web_interface.launch.py +++ b/launch/web_interface.launch.py @@ -196,23 +196,6 @@ def generate_launch_description(): stretch_has_nav_head_cam, ) - # If the stretch tool has the configuration(s) that require the specialized URDFs - # (e.g., move-to-pregrasp, enabled with the dex wrist, requires the specialized URDFs), - # check if the specialized URDFs exist and raise an exception if they don't. - if stretch_tool == "eoa_wrist_dw3_tool_sg3": - specialized_urdf_path = os.path.join( - teleop_interface_package, "urdf", "stretch_base_rotation_ik.urdf" - ) - if not os.path.exists(specialized_urdf_path): - raise FileNotFoundError( - "Could not find the specialized URDF, which is required for move-to-pregrasp, " - f"at {specialized_urdf_path}. Run the following:\n" - " 1. `colcon_cd stretch_web_teleop`\n" - " 2. `python3 prepare_specialized_urdf.py`\n" - " 3. `cd ~/ament_ws`\n" - " 4. `colcon build`" - ) - # Declare launch arguments params_file = DeclareLaunchArgument( "params", diff --git a/nodes/move_to_pregrasp.py b/nodes/move_to_pregrasp.py index 48f46ba6..c9d06893 100755 --- a/nodes/move_to_pregrasp.py +++ b/nodes/move_to_pregrasp.py @@ -49,6 +49,7 @@ MotionGeneratorRetval, StretchIKControl, ) +import urdf_utils as uu class MoveToPregraspNode(Node): @@ -100,14 +101,12 @@ def __init__( self.wrist_offset: Optional[Tuple[float, float]] = None # Create the inverse jacobian controller to execute motions - urdf_abs_path = os.path.join( - get_package_share_directory("stretch_web_teleop"), - "urdf/stretch_base_rotation_ik.urdf", - ) + urdf_fpaths = uu.generate_ik_urdfs("stretch_web_teleop", rigid_wrist_urdf=False) + urdf_fpath = urdf_fpaths[0] self.controller = StretchIKControl( self, tf_buffer=self.tf_buffer, - urdf_path=urdf_abs_path, + urdf_path=urdf_fpath, static_transform_broadcaster=self.static_transform_broadcaster, ) diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py index d378efd9..347e7ca3 100644 --- a/nodes/urdf_utils.py +++ b/nodes/urdf_utils.py @@ -257,7 +257,9 @@ def generate_ik_urdfs(app_name, rigid_wrist_urdf=True): ------- list(str): one or two filepaths, depending on `rigid_wrist_urdf`, - to the generated URDFs + to the generated URDFs. The first element will be the + full IK version, and the second will be the rigid + wrist version. """ robot = ud.Robot.from_xml_file(get_latest_urdf()) diff --git a/urdf/.placeholder b/urdf/.placeholder deleted file mode 100644 index e69de29b..00000000 From 2ba6b968dc4b85aba9a9a3ddc051f2555a89434f Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Wed, 9 Oct 2024 01:18:06 -0400 Subject: [PATCH 10/15] Remove preparation script --- prepare_specialized_urdf.py | 252 ------------------------------------ 1 file changed, 252 deletions(-) delete mode 100644 prepare_specialized_urdf.py diff --git a/prepare_specialized_urdf.py b/prepare_specialized_urdf.py deleted file mode 100644 index ecb64a03..00000000 --- a/prepare_specialized_urdf.py +++ /dev/null @@ -1,252 +0,0 @@ -# Standard imports -import pathlib -import pprint -import subprocess -import sys -from typing import Dict, Optional, Tuple - -# Third-party imports -import numpy as np -import stretch_body.hello_utils as hu -from urdf_parser_py import urdf as ud - - -def save_urdf_file(robot, file_name): - urdf_string = robot.to_xml_string() - print("Saving new URDF file to", file_name) - fid = open(file_name, "w") - fid.write(urdf_string) - fid.close() - print("Finished saving") - - -# Get the calibration directory -calibration_dir = pathlib.Path(hu.get_fleet_directory()) / "exported_urdf" -urdf_path = calibration_dir / "stretch.urdf" -controller_params_path = calibration_dir / "controller_calibration_head.yaml" -urdf_filename = str(urdf_path.absolute()) - -# Get the save directory -orig_pwd = pathlib.Path(__file__).parent.absolute() -if "stretch_web_teleop" not in str(orig_pwd): - subprocess.run(["colcon_cd", "stretch_web_teleop"]) - new_pwd = pathlib.Path(__file__).parent.absolute() - if "stretch_web_teleop" not in str(new_pwd): - raise RuntimeError( - "This script must be run from the stretch_web_teleop package. " - "Run `colcon_cd stretch_web_teleop` or `cd ~/ament_ws/src/stretch_web_teleop` " - "before running `python3 prepare_specialized_urdf.py`." - ) - else: - stretch_web_teleop_dir = new_pwd - subprocess.run(["cd", str(orig_pwd)]) -else: - stretch_web_teleop_dir = orig_pwd -save_dir = stretch_web_teleop_dir / "urdf" - -non_fixed_joints = [ - "joint_lift", - "joint_arm_l0", - "joint_arm_l1", - "joint_arm_l2", - "joint_arm_l3", - "joint_wrist_yaw", - "joint_wrist_pitch", - "joint_wrist_roll", -] - - -# Enables more conservative joint limits to be set than in the -# original URDF. Joint limits that are outside the originally -# permitted range will be clipped to the original range. Joint limits -# with a value of None will be set to the original limit. - -use_original_limits = True # False -ik_joint_limits: Dict[str, Tuple[Optional[float], Optional[float]]] = {} -if use_original_limits: - # Beware of gimbal lock if joint_wrist_pitch is too close to -90 deg - - ik_joint_limits = { - "joint_mobile_base_translation": (None, None), - "joint_mobile_base_rotation": (None, None), - "joint_lift": (None, None), - "joint_arm_l0": (None, None), - "joint_wrist_yaw": (None, None), - "joint_wrist_pitch": (-0.8 * (np.pi / 2.0), None), - "joint_wrist_roll": (None, None), - } -else: - ik_joint_limits = { - "joint_mobile_base_translation": (-0.25, 0.25), - "joint_mobile_base_rotation": (-(np.pi / 2.0), np.pi / 2.0), - "joint_lift": (0.01, 1.09), - "joint_arm_l0": (0.01, 0.48), - "joint_wrist_yaw": (-(np.pi / 4.0), np.pi), - "joint_wrist_pitch": (-0.9 * (np.pi / 2.0), np.pi / 20.0), - "joint_wrist_roll": (-(np.pi / 2.0), np.pi / 2.0), - } - - print("Setting new joint limits with ik_joint_limits =") - pprint.pprint(ik_joint_limits) - - -# Load and store the original uncalibrated URDF. -print() -print("Loading URDF from:") -print(urdf_filename) -print("The specialized URDFs will be derived from this URDF.") -try: - robot = ud.Robot.from_xml_file(urdf_filename) -except FileNotFoundError: - print( - f"The URDF file was not found in path {urdf_filename}. Unable to create specialized URDFs." - ) - sys.exit(0) - -# Change any joint that should be immobile for end effector IK into a fixed joint -for j in robot.joint_map.keys(): - if j not in non_fixed_joints: - joint = robot.joint_map[j] - # print('(joint name, joint type) =', (joint.name, joint.type)) - joint.type = "fixed" - -# Replace telescoping arm with a single prismatic joint - -# arm joints from proximal to distal -all_arm_joints = [ - "joint_arm_l4", - "joint_arm_l3", - "joint_arm_l2", - "joint_arm_l1", - "joint_arm_l0", -] - -prismatic_arm_joints = all_arm_joints[1:] - -removed_arm_joints = all_arm_joints[1:-1] - -xyz_total = np.array([0.0, 0.0, 0.0]) -limit_upper_total = 0.0 - -for j in prismatic_arm_joints: - joint = robot.joint_map[j] - # print(j + ' =', joint) - xyz = joint.origin.xyz - # print('xyz =', xyz) - xyz_total = xyz_total + xyz - limit_upper = joint.limit.upper - # print('limit_upper =', limit_upper) - limit_upper_total = limit_upper_total + limit_upper - -# print('xyz_total =', xyz_total) -# print('limit_upper_total =', limit_upper_total) - -proximal_arm_joint = robot.joint_map[all_arm_joints[0]] -near_proximal_arm_joint = robot.joint_map[all_arm_joints[1]] -near_distal_arm_joint = robot.joint_map[all_arm_joints[-2]] -distal_arm_joint = robot.joint_map[all_arm_joints[-1]] - -# Directly connect the proximal and distal parts of the arm -distal_arm_joint.parent = near_proximal_arm_joint.parent - -# Make the distal prismatic joint act like the full arm -distal_arm_joint.origin.xyz = xyz_total -distal_arm_joint.limit.upper = limit_upper_total - -# Make the telescoping joints in between immobile -for j in removed_arm_joints: - joint = robot.joint_map[j] - joint.type = "fixed" - - -robot_rotary = robot - -############################################### -# ADD VIRTUAL ROTARY JOINT FOR MOBILE BASE - -# Add a virtual base link -link_virtual_base_rotary = ud.Link( - name="virtual_base", visual=None, inertial=None, collision=None, origin=None -) - -# Add rotary joint for the mobile base -origin_rotary = ud.Pose(xyz=[0, 0, 0], rpy=[0, 0, 0]) - -limit_rotary = ud.JointLimit(effort=10, velocity=1, lower=-np.pi, upper=np.pi) - -joint_mobile_base_rotation = ud.Joint( - name="joint_mobile_base_rotation", - parent="virtual_base", - child="base_link", - joint_type="revolute", - axis=[0, 0, 1], - origin=origin_rotary, - limit=limit_rotary, - dynamics=None, - safety_controller=None, - calibration=None, - mimic=None, -) - -robot_rotary.add_link(link_virtual_base_rotary) -robot_rotary.add_joint(joint_mobile_base_rotation) -############################################### - -############################################### - -# When specified, this sets more conservative joint limits than the -# original URDF. Joint limits that are outside the originally -# permitted range are clipped to the original range. Joint limits -# with a value of None are set to the original limit. -for robot in [robot_rotary]: - for j in ik_joint_limits: - joint = robot.joint_map.get(j, None) - if joint is not None: - original_upper = joint.limit.upper - requested_upper = ik_joint_limits[j][1] - # print() - # print('joint =', j) - # print('original_upper =', original_upper) - # print('requested_upper =', requested_upper) - if requested_upper is not None: - new_upper = min(requested_upper, original_upper) - # print('new_upper =', new_upper) - robot.joint_map[j].limit.upper = new_upper - # print() - - original_lower = joint.limit.lower - requested_lower = ik_joint_limits[j][0] - if requested_lower is not None: - new_lower = max(requested_lower, original_lower) - robot.joint_map[j].limit.lower = new_lower - - -# print('************************************************') -# print('after adding link and joint: robot =', robot) -# print('************************************************') - -print() -save_urdf_file(robot_rotary, save_dir / "stretch_base_rotation_ik.urdf") - - -# Create versions with fixed wrists - -for robot in [robot_rotary]: - print("Prepare URDF with a fixed wrist.") - non_fixed_joints = [ - "joint_mobile_base_translation", - "joint_mobile_base_rotation", - "joint_lift", - "joint_arm_l0", - ] - - # Change any joint that should be immobile for end effector IK into a fixed joint - for j in robot.joint_map.keys(): - if j not in non_fixed_joints: - joint = robot.joint_map[j] - # print('(joint name, joint type) =', (joint.name, joint.type)) - joint.type = "fixed" - -save_urdf_file( - robot_rotary, save_dir / "stretch_base_rotation_ik_with_fixed_wrist.urdf" -) From c78b161dc039560fe9518ae5d174a61b246fc5be Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Wed, 9 Oct 2024 14:10:26 -0400 Subject: [PATCH 11/15] Switch to using Stretch URDF --- nodes/move_to_pregrasp.py | 2 +- nodes/urdf_utils.py | 306 -------------------------------------- 2 files changed, 1 insertion(+), 307 deletions(-) delete mode 100644 nodes/urdf_utils.py diff --git a/nodes/move_to_pregrasp.py b/nodes/move_to_pregrasp.py index c9d06893..4b515b8b 100755 --- a/nodes/move_to_pregrasp.py +++ b/nodes/move_to_pregrasp.py @@ -8,6 +8,7 @@ from typing import Dict, Generator, List, Optional, Tuple # Third-Party Imports +import stretch_urdf.urdf_utils as uu import numpy as np import numpy.typing as npt import rclpy @@ -49,7 +50,6 @@ MotionGeneratorRetval, StretchIKControl, ) -import urdf_utils as uu class MoveToPregraspNode(Node): diff --git a/nodes/urdf_utils.py b/nodes/urdf_utils.py deleted file mode 100644 index 347e7ca3..00000000 --- a/nodes/urdf_utils.py +++ /dev/null @@ -1,306 +0,0 @@ -import pathlib -import numpy as np -import stretch_body.hello_utils as hu -from urdf_parser_py import urdf as ud -from typing import Dict, Optional, Tuple - - -def get_latest_urdf(): - """ - Fetches the latest calibrated URDF from the calibration directory. - - Returns - ------- - str: Absolute filepath to the latest calibrated URDF. - """ - try: - fleet_dir = hu.get_fleet_directory() - except: - raise FileNotFoundError("Stretch data directory doesn't exist") from None - calibration_dir = pathlib.Path(fleet_dir) / "exported_urdf" - if not calibration_dir.is_dir(): - raise FileNotFoundError("URDF calibration directory doesn't exist") - urdf_path = calibration_dir / "stretch.urdf" - if not urdf_path.is_file(): - raise FileNotFoundError("URDF doesn't exist") - urdf_filename = str(urdf_path.absolute()) - return urdf_filename - - -def clip_joint_limits(robot, use_original_limits=True): - """ - Enables more conservative joint limits to be set than in the - original URDF. - - If these limits are outside the originally permitted range, - the original range is used. Joint limits. Where these limits - have a value of None, the original limit is used. - - Parameters - ---------- - robot: urdf_parser_py.urdf.Robot - a manipulable URDF representation - use_original_limits: bool - don't impose any additional limits - - Returns - ------- - urdf_parser_py.urdf.Robot: - modified URDF where joint limits are clipped - """ - ik_joint_limits: Dict[str, Tuple[Optional[float], Optional[float]]] = {} - if use_original_limits: - ik_joint_limits = { - "joint_mobile_base_translation": (None, None), - "joint_mobile_base_rotation": (None, None), - "joint_lift": (None, None), - "joint_arm_l0": (None, None), - "joint_wrist_yaw": (None, None), - "joint_wrist_pitch": (-0.8 * (np.pi / 2.0), None), # Beware of gimbal lock if joint_wrist_pitch is too close to -90 deg - "joint_wrist_roll": (None, None), - } - else: - ik_joint_limits = { - "joint_mobile_base_translation": (-0.25, 0.25), - "joint_mobile_base_rotation": (-(np.pi / 2.0), np.pi / 2.0), - "joint_lift": (0.01, 1.09), - "joint_arm_l0": (0.01, 0.48), - "joint_wrist_yaw": (-(np.pi / 4.0), np.pi), - "joint_wrist_pitch": (-0.9 * (np.pi / 2.0), np.pi / 20.0), - "joint_wrist_roll": (-(np.pi / 2.0), np.pi / 2.0), - } - - for j in ik_joint_limits: - joint = robot.joint_map.get(j, None) - if joint is not None: - original_upper = joint.limit.upper - requested_upper = ik_joint_limits[j][1] - if requested_upper is not None: - new_upper = min(requested_upper, original_upper) - robot.joint_map[j].limit.upper = new_upper - - original_lower = joint.limit.lower - requested_lower = ik_joint_limits[j][0] - if requested_lower is not None: - new_lower = max(requested_lower, original_lower) - robot.joint_map[j].limit.lower = new_lower - - -def make_joints_rigid(robot, ignore_joints=None): - """ - Change any joint that should be immobile for end effector IK - into a fixed joint. - - Parameters - ---------- - robot: urdf_parser_py.urdf.Robot - a manipulable URDF representation - ignore_joints: list(str) or None - which joints to keep as-is - - Returns - ------- - urdf_parser_py.urdf.Robot: - modified URDF where joints are "fixed" - """ - if ignore_joints is None: - ignore_joints = [] - - for j in robot.joint_map.keys(): - if j not in ignore_joints: - joint = robot.joint_map[j] - joint.type = "fixed" - - -def merge_arm(robot): - """ - Replace telescoping arm with a single prismatic joint, - which makes end-effector IK computation easier. - - Parameters - ---------- - robot: urdf_parser_py.urdf.Robot - a manipulable URDF representation - - Returns - ------- - urdf_parser_py.urdf.Robot: - modified URDF with single arm joint - """ - all_arm_joints = [ - "joint_arm_l4", - "joint_arm_l3", - "joint_arm_l2", - "joint_arm_l1", - "joint_arm_l0", - ] - prismatic_arm_joints = all_arm_joints[1:] - removed_arm_joints = all_arm_joints[1:-1] - near_proximal_arm_joint = robot.joint_map[all_arm_joints[1]] - distal_arm_joint = robot.joint_map[all_arm_joints[-1]] - - # Calculate aggregate joint characteristics - xyz_total = np.array([0.0, 0.0, 0.0]) - limit_upper_total = 0.0 - for j in prismatic_arm_joints: - joint = robot.joint_map[j] - xyz_total = xyz_total + joint.origin.xyz - limit_upper_total = limit_upper_total + joint.limit.upper - - # Directly connect the proximal and distal parts of the arm - distal_arm_joint.parent = near_proximal_arm_joint.parent - - # Make the distal prismatic joint act like the full arm - distal_arm_joint.origin.xyz = xyz_total - distal_arm_joint.limit.upper = limit_upper_total - - # Mark the eliminated joints as "fixed" - for j in removed_arm_joints: - joint = robot.joint_map[j] - joint.type = "fixed" - - -def add_virtual_rotary_joint(robot): - """ - Add virtual rotary joint for mobile base. - - Parameters - ---------- - robot: urdf_parser_py.urdf.Robot - a manipulable URDF representation - - Returns - ------- - urdf_parser_py.urdf.Robot: - modified URDF with mobile base rotation joint - """ - link_virtual_base_rotary = ud.Link( - name="virtual_base", visual=None, inertial=None, collision=None, origin=None - ) - origin_rotary = ud.Pose(xyz=[0, 0, 0], rpy=[0, 0, 0]) - limit_rotary = ud.JointLimit(effort=10, velocity=1, lower=-np.pi, upper=np.pi) - joint_mobile_base_rotation = ud.Joint( - name="joint_mobile_base_rotation", - parent="virtual_base", - child="base_link", - joint_type="revolute", - axis=[0, 0, 1], - origin=origin_rotary, - limit=limit_rotary, - dynamics=None, - safety_controller=None, - calibration=None, - mimic=None, - ) - robot.add_link(link_virtual_base_rotary) - robot.add_joint(joint_mobile_base_rotation) - - -def generate_urdf_from_robot(robot, app_name, description=None): - """ - Renders a `robot` URDF object out to a file in the /tmp - folder. The file will be unique to your application given - the `app_name` isn't the same as other applications. - - This enables you to safety generate URDFs on-the-fly - to be used by your app. E.g. `generate_ik_urdfs()` uses - this method to generate "calibrated" inverse kinematics - URDFs, so each robot's unique backlash and skew parameters - are baked into the IK calculations. - - Parameters - ---------- - robot: urdf_parser_py.urdf.Robot - the URDF representation to render out to a file - app_name: str - the name of your application - description: str or None - further description of the URDF - - Returns - ------- - str: filepath of the generated URDF - """ - if description is None: - description = "custom" - - def save_urdf(robot, file_name): - urdf_string = robot.to_xml_string() - with open(file_name, "w") as fid: - fid.write(urdf_string) - - filename = f'/tmp/{app_name}_{description}.urdf' - save_urdf(robot, filename) - - return filename - - -def generate_ik_urdfs(app_name, rigid_wrist_urdf=True): - """ - Generates URDFs for IK packages. The latest calibrated - URDF is used as a starting point, then these modifications - are applied: - 1. Clip joint limits - 2. Make non-IK joints rigid - 3. Merge arm joints - 4. Add virtual rotary base joint - 5. (optionally) Make wrist joints rigid - - Parameters - ---------- - app_name: str - the name of your application - rigid_wrist_urdf: bool or None - whether to also generate a IK URDF with a fixed dex wrist - - Returns - ------- - list(str): - one or two filepaths, depending on `rigid_wrist_urdf`, - to the generated URDFs. The first element will be the - full IK version, and the second will be the rigid - wrist version. - """ - - robot = ud.Robot.from_xml_file(get_latest_urdf()) - clip_joint_limits(robot) - - ignore_joints = [ - "joint_lift", - "joint_arm_l0", - "joint_arm_l1", - "joint_arm_l2", - "joint_arm_l3", - "joint_wrist_yaw", - "joint_wrist_pitch", - "joint_wrist_roll", - ] - make_joints_rigid(robot, ignore_joints) - - merge_arm(robot) - - add_virtual_rotary_joint(robot) - - ret = [] - fpath = generate_urdf_from_robot(robot, app_name, 'base_rotation_ik') - ret.append(fpath) - - if rigid_wrist_urdf: - ignore_joints = [ - "joint_mobile_base_translation", - "joint_mobile_base_rotation", - "joint_lift", - "joint_arm_l0", - ] - make_joints_rigid(robot, ignore_joints) - - fpath = generate_urdf_from_robot(robot, app_name, 'base_rotation_ik_with_fixed_wrist') - ret.append(fpath) - - return ret - - -if __name__ == "__main__": - print(generate_ik_urdfs('stretch_web_teleop')) - with open('/tmp/stretch_web_teleop_base_rotation_ik.urdf', 'r') as fid: - print(fid.read()) From 13fe2e9ca38fdb9e44cc5a76f6ab11d224579b97 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Wed, 9 Oct 2024 14:11:56 -0400 Subject: [PATCH 12/15] Add Stretch URDF dependency --- requirements.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/requirements.txt b/requirements.txt index 9961107d..fe111d01 100644 --- a/requirements.txt +++ b/requirements.txt @@ -8,3 +8,5 @@ pyquaternion pyttsx3 simpleaudio sounddevice +hello-robot-stretch-urdf>=0.1.0 + From 05bd339a068c9659c098b3b1dc305393547c9b6c Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Wed, 9 Oct 2024 14:39:49 -0400 Subject: [PATCH 13/15] CMake doesnt need to install urdf/ anymore --- CMakeLists.txt | 4 ---- 1 file changed, 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4aec4d27..f95d0010 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -58,10 +58,6 @@ install(DIRECTORY nodes DESTINATION share/${PROJECT_NAME} ) -install(DIRECTORY urdf - DESTINATION share/${PROJECT_NAME} -) - install(DIRECTORY config DESTINATION share/${PROJECT_NAME} ) From 7a7050bf0fda423f876c1adecfb2852d1be53cca Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Wed, 9 Oct 2024 15:07:55 -0400 Subject: [PATCH 14/15] Run prettier --- nodes/move_to_pregrasp.py | 5 +++-- requirements.txt | 3 +-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/nodes/move_to_pregrasp.py b/nodes/move_to_pregrasp.py index 4b515b8b..a20ae8fc 100755 --- a/nodes/move_to_pregrasp.py +++ b/nodes/move_to_pregrasp.py @@ -7,11 +7,12 @@ import traceback from typing import Dict, Generator, List, Optional, Tuple -# Third-Party Imports -import stretch_urdf.urdf_utils as uu import numpy as np import numpy.typing as npt import rclpy + +# Third-Party Imports +import stretch_urdf.urdf_utils as uu import tf2_ros import yaml from ament_index_python import get_package_share_directory diff --git a/requirements.txt b/requirements.txt index fe111d01..a48ddfe3 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,5 @@ gTTS +hello-robot-stretch-urdf>=0.1.0 loguru pin PyAudio==0.2.14 @@ -8,5 +9,3 @@ pyquaternion pyttsx3 simpleaudio sounddevice -hello-robot-stretch-urdf>=0.1.0 - From d47f5ccab5b42cfe4b55b31638ec304670114217 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Wed, 9 Oct 2024 15:08:44 -0400 Subject: [PATCH 15/15] Run prettier --- nodes/move_to_pregrasp.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/nodes/move_to_pregrasp.py b/nodes/move_to_pregrasp.py index a20ae8fc..e209a026 100755 --- a/nodes/move_to_pregrasp.py +++ b/nodes/move_to_pregrasp.py @@ -1,7 +1,6 @@ #!/usr/bin/env python3 # Standard Imports -import os import sys import threading import traceback @@ -15,7 +14,6 @@ import stretch_urdf.urdf_utils as uu import tf2_ros import yaml -from ament_index_python import get_package_share_directory from cv_bridge import CvBridge from geometry_msgs.msg import Point, Quaternion, Transform, TransformStamped, Vector3 from rclpy.action import ActionServer, CancelResponse, GoalResponse